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

#include <LPS22HB.hpp>

Inheritance diagram for LPS22HB:
Collaboration diagram for LPS22HB:

Public Member Functions

 LPS22HB (device::Device *interface, const char *path)
 
virtual ~LPS22HB ()
 
virtual int init ()
 
virtual int ioctl (struct file *filp, int cmd, unsigned long arg)
 
void print_info ()
 Diagnostics - print some basic information about the driver. More...
 
- Public Member Functions inherited from cdev::CDev
 CDev (const char *devname)
 Constructor. More...
 
 CDev (const CDev &)=delete
 
CDevoperator= (const CDev &)=delete
 
 CDev (CDev &&)=delete
 
CDevoperator= (CDev &&)=delete
 
virtual ~CDev ()
 
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 Attributes

device::Device_interface
 
- Protected Attributes inherited from cdev::CDev
px4_sem_t _lock
 lock to protect access to all class members (also for derived classes) More...
 

Private Member Functions

void start ()
 Initialise the automatic measurement state machine and start it. More...
 
void stop ()
 Stop the automatic measurement state machine. More...
 
int reset ()
 Reset the device. More...
 
void Run () override
 Perform a poll cycle; collect from the previous measurement and start a new one. More...
 
int write_reg (uint8_t reg, uint8_t val)
 Write a register. More...
 
int read_reg (uint8_t reg, uint8_t &val)
 Read a register. More...
 
int measure ()
 Issue a measurement command. More...
 
int collect ()
 Collect the result of the most recent measurement. More...
 
 LPS22HB (const LPS22HB &)
 
LPS22HB operator= (const LPS22HB &)
 

Private Attributes

unsigned _measure_interval {0}
 
bool _collect_phase {false}
 
orb_advert_t _baro_topic {nullptr}
 
int _orb_class_instance {-1}
 
int _class_instance {-1}
 
perf_counter_t _sample_perf
 
perf_counter_t _comms_errors
 
sensor_baro_s _last_report {}
 used for info() More...
 

Additional Inherited Members

- Protected Member Functions inherited from cdev::CDev
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...
 
- Static Protected Attributes inherited from cdev::CDev
static const px4_file_operations_t fops = {}
 Pointer to the default cdev file operations table; useful for registering clone devices etc. More...
 

Detailed Description

Definition at line 84 of file LPS22HB.hpp.

Constructor & Destructor Documentation

◆ LPS22HB() [1/2]

LPS22HB::LPS22HB ( device::Device interface,
const char *  path 
)

Definition at line 45 of file LPS22HB.cpp.

References _interface, DRV_BARO_DEVTYPE_LPS22HB, and device::Device::set_device_type().

Here is the call graph for this function:

◆ ~LPS22HB()

LPS22HB::~LPS22HB ( )
virtual

Definition at line 56 of file LPS22HB.cpp.

References _class_instance, _comms_errors, _interface, _sample_perf, BARO_BASE_DEVICE_PATH, perf_free(), stop(), and cdev::CDev::unregister_class_devname().

Here is the call graph for this function:

◆ LPS22HB() [2/2]

LPS22HB::LPS22HB ( const LPS22HB )
private

Member Function Documentation

◆ collect()

int LPS22HB::collect ( )
private

Collect the result of the most recent measurement.

Definition at line 248 of file LPS22HB.cpp.

References _baro_topic, _comms_errors, _interface, _last_report, _orb_class_instance, _sample_perf, sensor_baro_s::device_id, sensor_baro_s::error_count, device::Device::external(), device::Device::get_device_id(), hrt_absolute_time(), OK, orb_advertise_multi(), ORB_ID, ORB_PRIO_HIGH, ORB_PRIO_MAX, orb_publish(), P, perf_begin(), perf_count(), perf_end(), perf_event_count(), PRESS_OUT_H, PRESS_OUT_L, PRESS_OUT_XL, sensor_baro_s::pressure, device::Device::read(), STATUS, TEMP_OUT_H, TEMP_OUT_L, sensor_baro_s::temperature, and sensor_baro_s::timestamp.

Referenced by Run().

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

◆ init()

int LPS22HB::init ( )
virtual

Reimplemented from cdev::CDev.

Definition at line 73 of file LPS22HB.cpp.

References _class_instance, _measure_interval, BARO_BASE_DEVICE_PATH, ToneAlarmInterface::init(), LPS22HB_CONVERSION_INTERVAL, OK, cdev::CDev::register_class_devname(), reset(), and start().

Here is the call graph for this function:

◆ ioctl()

int LPS22HB::ioctl ( struct file filp,
int  cmd,
unsigned long  arg 
)
virtual

Definition at line 100 of file LPS22HB.cpp.

References _interface, _measure_interval, device::Device::ioctl(), LPS22HB_CONVERSION_INTERVAL, OK, reset(), SENSOR_POLLRATE_DEFAULT, SENSORIOCRESET, SENSORIOCSPOLLRATE, and start().

Here is the call graph for this function:

◆ measure()

int LPS22HB::measure ( )
private

Issue a measurement command.

Returns
OK if the measurement command was successful.

Definition at line 235 of file LPS22HB.cpp.

References _comms_errors, CTRL_REG2, IF_ADD_INC, OK, ONE_SHOT, perf_count(), and write_reg().

Referenced by Run().

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

◆ operator=()

LPS22HB LPS22HB::operator= ( const LPS22HB )
private

◆ print_info()

void LPS22HB::print_info ( )

Diagnostics - print some basic information about the driver.

Definition at line 327 of file LPS22HB.cpp.

References _comms_errors, _last_report, _measure_interval, _sample_perf, and perf_print_counter().

Here is the call graph for this function:

◆ read_reg()

int LPS22HB::read_reg ( uint8_t  reg,
uint8_t &  val 
)
private

Read a register.

Parameters
regThe register to read.
valThe value read.
Returns
OK on read success.

Definition at line 318 of file LPS22HB.cpp.

References _interface, and device::Device::read().

Here is the call graph for this function:

◆ reset()

int LPS22HB::reset ( )
private

Reset the device.

Definition at line 184 of file LPS22HB.cpp.

References BOOT, CTRL_REG2, SWRESET, and write_reg().

Referenced by init(), and ioctl().

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

◆ Run()

void LPS22HB::Run ( )
overrideprivate

Perform a poll cycle; collect from the previous measurement and start a new one.

This is the heart of the measurement state machine. This function alternately starts a measurement, or collects the data from the previous measurement.

When the interval between measurements is greater than the minimum measurement interval, a gap is inserted between collection and measurement to provide the most recent measurement possible at the next interval.

Definition at line 194 of file LPS22HB.cpp.

References _collect_phase, _measure_interval, collect(), LPS22HB_CONVERSION_INTERVAL, measure(), OK, and start().

Here is the call graph for this function:

◆ start()

void LPS22HB::start ( )
private

Initialise the automatic measurement state machine and start it.

Note
This function is called at open and error time. It might make sense to make it more aggressive about resetting the bus in case of errors.

Definition at line 168 of file LPS22HB.cpp.

References _collect_phase.

Referenced by init(), ioctl(), and Run().

Here is the caller graph for this function:

◆ stop()

void LPS22HB::stop ( )
private

Stop the automatic measurement state machine.

Definition at line 178 of file LPS22HB.cpp.

Referenced by ~LPS22HB().

Here is the caller graph for this function:

◆ write_reg()

int LPS22HB::write_reg ( uint8_t  reg,
uint8_t  val 
)
private

Write a register.

Parameters
regThe register to write.
valThe value to write.
Returns
OK on write success.

Definition at line 311 of file LPS22HB.cpp.

References _interface, and device::Device::write().

Referenced by measure(), and reset().

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

Member Data Documentation

◆ _baro_topic

orb_advert_t LPS22HB::_baro_topic {nullptr}
private

Definition at line 107 of file LPS22HB.hpp.

Referenced by collect().

◆ _class_instance

int LPS22HB::_class_instance {-1}
private

Definition at line 110 of file LPS22HB.hpp.

Referenced by init(), and ~LPS22HB().

◆ _collect_phase

bool LPS22HB::_collect_phase {false}
private

Definition at line 105 of file LPS22HB.hpp.

Referenced by Run(), and start().

◆ _comms_errors

perf_counter_t LPS22HB::_comms_errors
private

Definition at line 113 of file LPS22HB.hpp.

Referenced by collect(), measure(), print_info(), and ~LPS22HB().

◆ _interface

device::Device* LPS22HB::_interface
protected

Definition at line 100 of file LPS22HB.hpp.

Referenced by collect(), ioctl(), LPS22HB(), read_reg(), write_reg(), and ~LPS22HB().

◆ _last_report

sensor_baro_s LPS22HB::_last_report {}
private

used for info()

Definition at line 115 of file LPS22HB.hpp.

Referenced by collect(), and print_info().

◆ _measure_interval

unsigned LPS22HB::_measure_interval {0}
private

Definition at line 103 of file LPS22HB.hpp.

Referenced by init(), ioctl(), print_info(), and Run().

◆ _orb_class_instance

int LPS22HB::_orb_class_instance {-1}
private

Definition at line 109 of file LPS22HB.hpp.

Referenced by collect().

◆ _sample_perf

perf_counter_t LPS22HB::_sample_perf
private

Definition at line 112 of file LPS22HB.hpp.

Referenced by collect(), print_info(), and ~LPS22HB().


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