PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Abstract class for any character device. More...
#include <CDev.hpp>
Public Member Functions | |
CDev (const char *devname) | |
Constructor. More... | |
CDev (const CDev &)=delete | |
CDev & | operator= (const CDev &)=delete |
CDev (CDev &&)=delete | |
CDev & | operator= (CDev &&)=delete |
virtual | ~CDev () |
virtual int | init () |
virtual int | open (file_t *filep) |
Handle an open of the device. More... | |
virtual int | close (file_t *filep) |
Handle a close of the device. More... | |
virtual ssize_t | read (file_t *filep, char *buffer, size_t buflen) |
Perform a read from the device. More... | |
virtual ssize_t | write (file_t *filep, const char *buffer, size_t buflen) |
Perform a write to the device. More... | |
virtual off_t | seek (file_t *filep, off_t offset, int whence) |
Perform a logical seek operation on the device. More... | |
virtual int | ioctl (file_t *filep, int cmd, unsigned long arg) |
Perform an ioctl operation on the device. More... | |
virtual int | poll (file_t *filep, px4_pollfd_struct_t *fds, bool setup) |
Perform a poll setup/teardown operation. More... | |
const char * | get_devname () const |
Get the device name. More... | |
Protected Member Functions | |
virtual pollevent_t | poll_state (file_t *filep) |
Check the current state of the device for poll events from the perspective of the file. More... | |
virtual void | poll_notify (pollevent_t events) |
Report new poll events. More... | |
virtual void | poll_notify_one (px4_pollfd_struct_t *fds, pollevent_t events) |
Internal implementation of poll_notify. More... | |
virtual int | open_first (file_t *filep) |
Notification of the first open. More... | |
virtual int | close_last (file_t *filep) |
Notification of the last close. More... | |
virtual int | register_class_devname (const char *class_devname) |
Register a class device name, automatically adding device class instance suffix if need be. More... | |
virtual int | unregister_class_devname (const char *class_devname, unsigned class_instance) |
Register a class device name, automatically adding device class instance suffix if need be. More... | |
void | lock () |
Take the driver lock. More... | |
void | unlock () |
Release the driver lock. More... | |
int | unregister_driver_and_memory () |
First, unregisters the driver. More... | |
Protected Attributes | |
px4_sem_t | _lock |
lock to protect access to all class members (also for derived classes) More... | |
Static Protected Attributes | |
static const px4_file_operations_t | fops = {} |
Pointer to the default cdev file operations table; useful for registering clone devices etc. More... | |
Private Member Functions | |
int | store_poll_waiter (px4_pollfd_struct_t *fds) |
Store a pollwaiter in a slot where we can find it later. More... | |
int | remove_poll_waiter (px4_pollfd_struct_t *fds) |
Remove a poll waiter. More... | |
Private Attributes | |
const char * | _devname {nullptr} |
device node name More... | |
px4_pollfd_struct_t ** | _pollset {nullptr} |
bool | _registered {false} |
true if device name was registered More... | |
uint8_t | _max_pollwaiters {0} |
size of the _pollset array More... | |
uint16_t | _open_count {0} |
number of successful opens More... | |
|
explicit |
|
delete |
|
delete |
|
virtual |
Reimplemented in device::CDev.
Definition at line 62 of file CDev.cpp.
References _devname, _lock, _pollset, _registered, and unregister_driver().
|
virtual |
Handle a close of the device.
This function is called for every close of the device. The default implementation maintains _open_count and returns OK as long as it is not zero.
filep | Pointer to the NuttX file structure. |
Reimplemented in CDevNode, and uORB::DeviceNode.
Definition at line 166 of file CDev.cpp.
References _open_count, close_last(), lock(), and unlock().
Referenced by cdev::cdev_close(), IridiumSBD::main_loop_helper(), Radar::open_serial_port(), LeddarOne::open_serial_port(), PX4IO::print_debug(), pwmin_reset(), pwmin_test(), px4_close(), PX4IO::set_update_rate(), mpl3115a2::start_bus(), lps25h::start_bus(), qmc5883::start_bus(), IridiumSBD::stop(), LeddarOne::stop(), Radar::stop(), PX4FMU::test(), leddar_one::test(), mpl3115a2::test(), and lps25h::test().
|
inlineprotectedvirtual |
Notification of the last close.
This function is called when the device open count transitions from one to zero. The driver lock is held for the duration of the call.
The default implementation returns OK.
filep | Pointer to the NuttX file structure. |
Definition at line 234 of file CDev.hpp.
Referenced by close().
|
inline |
Get the device name.
Definition at line 169 of file CDev.hpp.
Referenced by device::CDev::init(), MPL3115A2::~MPL3115A2(), and MS5611::~MS5611().
|
virtual |
Reimplemented in PWMIN, LPS25H, PX4IO, PX4FMU, QMC5883, DShotOutput, RM3100, HMC5883, Radar, LIS3MDL, LeddarOne, TAP_ESC, MS5611, LPS22HB, SF0X, device::CDev, MPL3115A2, ADC, LED, ToneAlarm, LED, UavcanMagnetometerBridge, UavcanBarometerBridge, UavcanBatteryBridge, and UavcanFlowBridge.
Definition at line 119 of file CDev.cpp.
References _devname, _registered, fops, and register_driver().
Referenced by uORB::DeviceMaster::advertise(), and device::CDev::init().
|
virtual |
Perform an ioctl operation on the device.
The default implementation handles DIOC_GETPRIV, and otherwise returns -ENOTTY. Subclasses should call the default implementation for any command they do not handle themselves.
filep | Pointer to the NuttX file structure. |
cmd | The ioctl command value. |
arg | The ioctl argument value. |
Reimplemented in HMC5883, uORB::DeviceNode, TAP_ESC, MS5611, SF0X, device::CDev, PWMSim, LED, PX4Gyroscope, PX4Accelerometer, and PX4Magnetometer.
Definition at line 192 of file CDev.cpp.
Referenced by cdev::cdev_ioctl(), and px4_ioctl().
|
inlineprotected |
Take the driver lock.
Each driver instance has its own lock/semaphore.
Note that we must loop as the wait may be interrupted by a signal.
Careful: lock() calls cannot be nested!
Definition at line 264 of file CDev.hpp.
Referenced by uORB::DeviceNode::add_internal_subscriber(), PX4FMU::capture_ioctl(), DShotOutput::capture_ioctl(), close(), PWMSim::ioctl(), UavcanEsc::ioctl(), uORB::DeviceNode::ioctl(), UavcanNode::ioctl(), UavcanMagnetometerBridge::mag2_sub_cb(), UavcanMagnetometerBridge::mag_sub_cb(), uORB::DeviceNode::open(), open(), uORB::DeviceNode::print_statistics(), PX4FMU::pwm_ioctl(), DShotOutput::pwm_ioctl(), Mavlink2Dev::read(), RtpsDev::read(), uORB::DeviceNode::remove_internal_subscriber(), PX4IO::task_main(), uORB::DeviceNode::write(), Mavlink2Dev::write(), and RtpsDev::write().
|
virtual |
Handle an open of the device.
This function is called for every open of the device. The default implementation maintains _open_count and always returns OK.
filep | Pointer to the NuttX file structure. |
Reimplemented in CDevNode, and uORB::DeviceNode.
Definition at line 141 of file CDev.cpp.
References _open_count, lock(), open_first(), and unlock().
Referenced by cdev::cdev_open(), Radar::open_serial_port(), LeddarOne::open_serial_port(), IridiumSBD::open_uart(), PX4IO::print_debug(), px4_open(), mpl3115a2::reset(), sf0x::reset(), lps25h::reset(), qmc5883::reset(), SF0X::Run(), ADC::sample(), PX4IO::set_update_rate(), sf0x::start(), mpl3115a2::start_bus(), lps25h::start_bus(), qmc5883::start_bus(), PX4FMU::test(), radar::test(), leddar_one::test(), mpl3115a2::test(), sf0x::test(), lps25h::test(), and qmc5883::test().
|
inlineprotectedvirtual |
Notification of the first open.
This function is called when the device open count transitions from zero to one. The driver lock is held for the duration of the call.
The default implementation returns OK.
filep | Pointer to the NuttX file structure. |
Definition at line 221 of file CDev.hpp.
Referenced by open().
|
virtual |
Perform a poll setup/teardown operation.
This is handled internally and should not normally be overridden.
filep | Pointer to the internal file structure. |
fds | Poll descriptor being waited on. |
setup | True if this is establishing a request, false if it is being torn down. |
Definition at line 213 of file CDev.cpp.
References _max_pollwaiters, _pollset, ATOMIC_ENTER, ATOMIC_LEAVE, poll_state(), remove_poll_waiter(), and store_poll_waiter().
Referenced by LIS3MDL::calibrate(), cdev::cdev_poll(), DevCommon::poll_state(), PX4IO::print_debug(), px4_poll(), IridiumSBD::read_at(), PX4IO::set_update_rate(), PX4IO::task_main(), PX4FMU::test(), mpl3115a2::test(), sf0x::test(), lps25h::test(), and qmc5883::test().
|
protectedvirtual |
Report new poll events.
This function should be called anytime the state of the device changes in a fashion that might be interesting to a poll waiter.
events | The new event(s) being announced. |
Definition at line 330 of file CDev.cpp.
References _max_pollwaiters, _pollset, ATOMIC_ENTER, ATOMIC_LEAVE, and poll_notify_one().
Referenced by Radar::collect(), MPL3115A2::collect(), SF0X::collect(), MS5611::collect(), RM3100::collect(), LIS3MDL::collect(), QMC5883::collect(), LPS25H::collect(), HMC5883::collect(), PX4Barometer::update(), PX4Magnetometer::update(), PX4Accelerometer::update(), PX4Gyroscope::update(), cdev::VFile::write(), and uORB::DeviceNode::write().
|
protectedvirtual |
Internal implementation of poll_notify.
fds | A poll waiter to notify. |
events | The event(s) to send to the waiter. |
Reimplemented in uORB::DeviceNode.
Definition at line 347 of file CDev.cpp.
Referenced by poll_notify().
|
inlineprotectedvirtual |
Check the current state of the device for poll events from the perspective of the file.
This function is called by the default poll() implementation when a poll is set up to determine whether the poll should return immediately.
The default implementation returns no events.
filep | The file that's interested. |
Reimplemented in uORB::DeviceNode.
Definition at line 190 of file CDev.hpp.
Referenced by poll().
|
inlinevirtual |
Perform a read from the device.
The default implementation returns -ENOSYS.
filep | Pointer to the NuttX file structure. |
buffer | Pointer to the buffer into which data should be placed. |
buflen | The number of bytes to be read. |
Reimplemented in HMC5883, CDevNode, MS5611, uORB::DeviceNode, and SF0X.
Definition at line 111 of file CDev.hpp.
Referenced by cdev::cdev_read(), Radar::collect(), LeddarOne::collect(), PX4IO::print_debug(), px4_read(), PX4IO::set_update_rate(), PX4FMU::test(), radar::test(), leddar_one::test(), and Mavlink2Dev::~Mavlink2Dev().
|
protectedvirtual |
Register a class device name, automatically adding device class instance suffix if need be.
class_devname | Device class name |
Definition at line 78 of file CDev.cpp.
References fops, name, OK, and register_driver().
Referenced by MPL3115A2::init(), SF0X::init(), LPS22HB::init(), MS5611::init(), LIS3MDL::init(), HMC5883::init(), RM3100::init(), DShotOutput::init(), QMC5883::init(), PX4FMU::init(), LPS25H::init(), PX4Accelerometer::PX4Accelerometer(), PX4Barometer::PX4Barometer(), PX4Gyroscope::PX4Gyroscope(), PX4Magnetometer::PX4Magnetometer(), and PX4Rangefinder::PX4Rangefinder().
|
inlineprivate |
Remove a poll waiter.
Definition at line 381 of file CDev.cpp.
References _max_pollwaiters, and _pollset.
Referenced by poll().
|
inlinevirtual |
Perform a logical seek operation on the device.
The default implementation returns -ENOSYS.
filep | Pointer to the NuttX file structure. |
offset | The new file position relative to whence. |
whence | SEEK_OFS, SEEK_CUR or SEEK_END. |
Definition at line 135 of file CDev.hpp.
Referenced by cdev::cdev_seek().
|
inlineprivate |
Store a pollwaiter in a slot where we can find it later.
Expands the pollset as required. Must be called with the driver locked.
Definition at line 362 of file CDev.cpp.
References _max_pollwaiters, and _pollset.
Referenced by poll().
|
inlineprotected |
Release the driver lock.
Definition at line 269 of file CDev.hpp.
Referenced by uORB::DeviceNode::add_internal_subscriber(), PX4FMU::capture_ioctl(), DShotOutput::capture_ioctl(), close(), PWMSim::ioctl(), UavcanEsc::ioctl(), uORB::DeviceNode::ioctl(), UavcanNode::ioctl(), UavcanMagnetometerBridge::mag2_sub_cb(), UavcanMagnetometerBridge::mag_sub_cb(), uORB::DeviceNode::open(), open(), uORB::DeviceNode::print_statistics(), PX4FMU::pwm_ioctl(), DShotOutput::pwm_ioctl(), Mavlink2Dev::read(), RtpsDev::read(), uORB::DeviceNode::remove_internal_subscriber(), PX4IO::task_main(), uORB::DeviceNode::write(), Mavlink2Dev::write(), and RtpsDev::write().
|
protectedvirtual |
Register a class device name, automatically adding device class instance suffix if need be.
class_devname | Device class name |
class_instance | Device class instance from register_class_devname() |
Definition at line 109 of file CDev.cpp.
References name, and unregister_driver().
Referenced by DShotOutput::~DShotOutput(), HMC5883::~HMC5883(), LIS3MDL::~LIS3MDL(), LPS22HB::~LPS22HB(), LPS25H::~LPS25H(), MPL3115A2::~MPL3115A2(), MS5611::~MS5611(), PX4Accelerometer::~PX4Accelerometer(), PX4Barometer::~PX4Barometer(), PX4FMU::~PX4FMU(), PX4Gyroscope::~PX4Gyroscope(), PX4Magnetometer::~PX4Magnetometer(), PX4Rangefinder::~PX4Rangefinder(), QMC5883::~QMC5883(), RM3100::~RM3100(), and SF0X::~SF0X().
|
protected |
First, unregisters the driver.
Next, free the memory for the devname, in case it was expected to have ownership. Sets devname to nullptr.
This is only needed if the ownership of the devname was passed to the CDev, otherwise ~CDev handles it.
Definition at line 398 of file CDev.cpp.
References _devname, _registered, and unregister_driver().
|
inlinevirtual |
Perform a write to the device.
The default implementation returns -ENOSYS.
filep | Pointer to the NuttX file structure. |
buffer | Pointer to the buffer from which data should be read. |
buflen | The number of bytes to be written. |
Reimplemented in CDevNode, uORB::DeviceNode, and cdev::VFile.
Definition at line 123 of file CDev.hpp.
Referenced by cdev::cdev_write(), LeddarOne::measure(), SF0X::measure(), px4_write(), leddar_one::test(), and Mavlink2Dev::~Mavlink2Dev().
|
private |
device node name
Definition at line 285 of file CDev.hpp.
Referenced by init(), unregister_driver_and_memory(), and ~CDev().
|
protected |
lock to protect access to all class members (also for derived classes)
Definition at line 271 of file CDev.hpp.
Referenced by CDev(), PX4IO::ioctl(), and ~CDev().
|
private |
size of the _pollset array
Definition at line 291 of file CDev.hpp.
Referenced by poll(), poll_notify(), remove_poll_waiter(), and store_poll_waiter().
|
private |
|
private |
Definition at line 287 of file CDev.hpp.
Referenced by poll(), poll_notify(), remove_poll_waiter(), store_poll_waiter(), and ~CDev().
|
private |
true if device name was registered
Definition at line 289 of file CDev.hpp.
Referenced by init(), unregister_driver_and_memory(), and ~CDev().
|
staticprotected |
Pointer to the default cdev file operations table; useful for registering clone devices etc.
Definition at line 176 of file CDev.hpp.
Referenced by init(), PX4IO::init(), and register_class_devname().