PX4 Firmware
PX4 Autopilot Software http://px4.io
cdev::CDev Class Reference

Abstract class for any character device. More...

#include <CDev.hpp>

Inheritance diagram for cdev::CDev:
Collaboration diagram for cdev::CDev:

Public Member Functions

 CDev (const char *devname)
 Constructor. More...
 
 CDev (const CDev &)=delete
 
CDevoperator= (const CDev &)=delete
 
 CDev (CDev &&)=delete
 
CDevoperator= (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...
 

Detailed Description

Abstract class for any character device.

Definition at line 58 of file CDev.hpp.

Constructor & Destructor Documentation

◆ CDev() [1/3]

CDev::CDev ( const char *  devname)
explicit

Constructor.

Parameters
nameDriver name
devnameDevice node name

Definition at line 50 of file CDev.cpp.

References _lock.

◆ CDev() [2/3]

cdev::CDev::CDev ( const CDev )
delete

◆ CDev() [3/3]

cdev::CDev::CDev ( CDev &&  )
delete

◆ ~CDev()

CDev::~CDev ( )
virtual

Reimplemented in device::CDev.

Definition at line 62 of file CDev.cpp.

References _devname, _lock, _pollset, _registered, and unregister_driver().

Here is the call graph for this function:

Member Function Documentation

◆ close()

int CDev::close ( file_t filep)
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.

Parameters
filepPointer to the NuttX file structure.
Returns
OK if the close was successful, -errno otherwise.

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ close_last()

virtual int cdev::CDev::close_last ( file_t filep)
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.

Parameters
filepPointer to the NuttX file structure.
Returns
OK if the open should return OK, -errno otherwise.

Definition at line 234 of file CDev.hpp.

Referenced by close().

Here is the caller graph for this function:

◆ get_devname()

const char* cdev::CDev::get_devname ( ) const
inline

Get the device name.

Returns
the file system string of the device handle

Definition at line 169 of file CDev.hpp.

Referenced by device::CDev::init(), MPL3115A2::~MPL3115A2(), and MS5611::~MS5611().

Here is the caller graph for this function:

◆ init()

int CDev::init ( )
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ioctl()

int CDev::ioctl ( file_t filep,
int  cmd,
unsigned long  arg 
)
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.

Parameters
filepPointer to the NuttX file structure.
cmdThe ioctl command value.
argThe ioctl argument value.
Returns
OK on success, or -errno otherwise.

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().

Here is the caller graph for this function:

◆ lock()

void cdev::CDev::lock ( )
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().

Here is the caller graph for this function:

◆ open()

int CDev::open ( file_t filep)
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.

Parameters
filepPointer to the NuttX file structure.
Returns
OK if the open is allowed, -errno otherwise.

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ open_first()

virtual int cdev::CDev::open_first ( file_t filep)
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.

Parameters
filepPointer to the NuttX file structure.
Returns
OK if the open should proceed, -errno otherwise.

Definition at line 221 of file CDev.hpp.

Referenced by open().

Here is the caller graph for this function:

◆ operator=() [1/2]

CDev& cdev::CDev::operator= ( const CDev )
delete

◆ operator=() [2/2]

CDev& cdev::CDev::operator= ( CDev &&  )
delete

◆ poll()

int CDev::poll ( file_t filep,
px4_pollfd_struct_t *  fds,
bool  setup 
)
virtual

Perform a poll setup/teardown operation.

This is handled internally and should not normally be overridden.

Parameters
filepPointer to the internal file structure.
fdsPoll descriptor being waited on.
setupTrue if this is establishing a request, false if it is being torn down.
Returns
OK on success, or -errno otherwise.

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ poll_notify()

void CDev::poll_notify ( pollevent_t  events)
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.

Parameters
eventsThe 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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ poll_notify_one()

void CDev::poll_notify_one ( px4_pollfd_struct_t *  fds,
pollevent_t  events 
)
protectedvirtual

Internal implementation of poll_notify.

Parameters
fdsA poll waiter to notify.
eventsThe event(s) to send to the waiter.

Reimplemented in uORB::DeviceNode.

Definition at line 347 of file CDev.cpp.

Referenced by poll_notify().

Here is the caller graph for this function:

◆ poll_state()

virtual pollevent_t cdev::CDev::poll_state ( file_t filep)
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.

Parameters
filepThe file that's interested.
Returns
The current set of poll events.

Reimplemented in uORB::DeviceNode.

Definition at line 190 of file CDev.hpp.

Referenced by poll().

Here is the caller graph for this function:

◆ read()

virtual ssize_t cdev::CDev::read ( file_t filep,
char *  buffer,
size_t  buflen 
)
inlinevirtual

Perform a read from the device.

The default implementation returns -ENOSYS.

Parameters
filepPointer to the NuttX file structure.
bufferPointer to the buffer into which data should be placed.
buflenThe number of bytes to be read.
Returns
The number of bytes read or -errno otherwise.

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().

Here is the caller graph for this function:

◆ register_class_devname()

int CDev::register_class_devname ( const char *  class_devname)
protectedvirtual

Register a class device name, automatically adding device class instance suffix if need be.

Parameters
class_devnameDevice class name
Returns
class_instamce Class instance created, or -errno on failure

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ remove_poll_waiter()

int CDev::remove_poll_waiter ( px4_pollfd_struct_t *  fds)
inlineprivate

Remove a poll waiter.

Returns
OK, or -errno on error.

Definition at line 381 of file CDev.cpp.

References _max_pollwaiters, and _pollset.

Referenced by poll().

Here is the caller graph for this function:

◆ seek()

virtual off_t cdev::CDev::seek ( file_t filep,
off_t  offset,
int  whence 
)
inlinevirtual

Perform a logical seek operation on the device.

The default implementation returns -ENOSYS.

Parameters
filepPointer to the NuttX file structure.
offsetThe new file position relative to whence.
whenceSEEK_OFS, SEEK_CUR or SEEK_END.
Returns
The previous offset, or -errno otherwise.

Definition at line 135 of file CDev.hpp.

Referenced by cdev::cdev_seek().

Here is the caller graph for this function:

◆ store_poll_waiter()

int CDev::store_poll_waiter ( px4_pollfd_struct_t *  fds)
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.

Returns
OK, or -errno on error.

Definition at line 362 of file CDev.cpp.

References _max_pollwaiters, and _pollset.

Referenced by poll().

Here is the caller graph for this function:

◆ unlock()

◆ unregister_class_devname()

int CDev::unregister_class_devname ( const char *  class_devname,
unsigned  class_instance 
)
protectedvirtual

Register a class device name, automatically adding device class instance suffix if need be.

Parameters
class_devnameDevice class name
class_instanceDevice class instance from register_class_devname()
Returns
OK on success, -errno otherwise

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ unregister_driver_and_memory()

int CDev::unregister_driver_and_memory ( )
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.

Returns
PX4_OK on success, -ENODEV if the devname is already nullptr

Definition at line 398 of file CDev.cpp.

References _devname, _registered, and unregister_driver().

Here is the call graph for this function:

◆ write()

virtual ssize_t cdev::CDev::write ( file_t filep,
const char *  buffer,
size_t  buflen 
)
inlinevirtual

Perform a write to the device.

The default implementation returns -ENOSYS.

Parameters
filepPointer to the NuttX file structure.
bufferPointer to the buffer from which data should be read.
buflenThe number of bytes to be written.
Returns
The number of bytes written or -errno otherwise.

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().

Here is the caller graph for this function:

Member Data Documentation

◆ _devname

const char* cdev::CDev::_devname {nullptr}
private

device node name

Definition at line 285 of file CDev.hpp.

Referenced by init(), unregister_driver_and_memory(), and ~CDev().

◆ _lock

px4_sem_t cdev::CDev::_lock
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().

◆ _max_pollwaiters

uint8_t cdev::CDev::_max_pollwaiters {0}
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().

◆ _open_count

uint16_t cdev::CDev::_open_count {0}
private

number of successful opens

Definition at line 292 of file CDev.hpp.

Referenced by close(), and open().

◆ _pollset

px4_pollfd_struct_t** cdev::CDev::_pollset {nullptr}
private

Definition at line 287 of file CDev.hpp.

Referenced by poll(), poll_notify(), remove_poll_waiter(), store_poll_waiter(), and ~CDev().

◆ _registered

bool cdev::CDev::_registered {false}
private

true if device name was registered

Definition at line 289 of file CDev.hpp.

Referenced by init(), unregister_driver_and_memory(), and ~CDev().

◆ fops

const cdev::px4_file_operations_t CDev::fops = {}
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().


The documentation for this class was generated from the following files: