PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <MS5611.hpp>
Public Member Functions | |
MS5611 (device::Device *interface, ms5611::prom_u &prom_buf, const char *path, enum MS56XX_DEVICE_TYPES device_type) | |
~MS5611 () | |
virtual int | init () |
virtual ssize_t | read (cdev::file_t *filp, char *buffer, size_t buflen) |
Perform a read from the device. More... | |
virtual int | ioctl (cdev::file_t *filp, int cmd, unsigned long arg) |
Perform an ioctl operation on the device. More... | |
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 | |
CDev & | operator= (const CDev &)=delete |
CDev (CDev &&)=delete | |
CDev & | operator= (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 | 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 | 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 | |
void | start () |
Initialize the automatic measurement state machine and start it. More... | |
void | stop () |
Stop the automatic measurement state machine. More... | |
void | Run () override |
Perform a poll cycle; collect from the previous measurement and start a new one. More... | |
virtual int | measure () |
Issue a measurement command for the current state. More... | |
virtual int | collect () |
Collect the result of the most recent measurement. More... | |
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... | |
Protected Attributes | |
device::Device * | _interface |
ms5611::prom_s | _prom |
unsigned | _measure_interval {0} |
ringbuffer::RingBuffer * | _reports |
enum MS56XX_DEVICE_TYPES | _device_type |
bool | _collect_phase |
unsigned | _measure_phase |
int32_t | _TEMP |
int64_t | _OFF |
int64_t | _SENS |
float | _P |
float | _T |
orb_advert_t | _baro_topic |
int | _orb_class_instance |
int | _class_instance |
perf_counter_t | _sample_perf |
perf_counter_t | _measure_perf |
perf_counter_t | _comms_errors |
Protected Attributes inherited from cdev::CDev | |
px4_sem_t | _lock |
lock to protect access to all class members (also for derived classes) More... | |
Additional Inherited Members | |
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... | |
Definition at line 95 of file MS5611.hpp.
MS5611::MS5611 | ( | device::Device * | interface, |
ms5611::prom_u & | prom_buf, | ||
const char * | path, | ||
enum MS56XX_DEVICE_TYPES | device_type | ||
) |
Definition at line 44 of file ms5611.cpp.
MS5611::~MS5611 | ( | ) |
Definition at line 66 of file ms5611.cpp.
References _class_instance, _comms_errors, _interface, _measure_perf, _reports, _sample_perf, cdev::CDev::get_devname(), perf_free(), stop(), and cdev::CDev::unregister_class_devname().
|
protectedvirtual |
Collect the result of the most recent measurement.
Definition at line 461 of file ms5611.cpp.
References _baro_topic, _comms_errors, _device_type, _interface, _measure_phase, _OFF, _P, _prom, _reports, _sample_perf, _SENS, _T, _TEMP, ms5611::prom_s::c1_pressure_sens, ms5611::prom_s::c2_pressure_offset, ms5611::prom_s::c3_temp_coeff_pres_sens, ms5611::prom_s::c4_temp_coeff_pres_offset, ms5611::prom_s::c5_reference_temp, ms5611::prom_s::c6_temp_coeff_temp, sensor_baro_s::device_id, sensor_baro_s::error_count, f(), device::Device::get_device_id(), hrt_absolute_time(), INCREMENT, MS5607_DEVICE, MS5611_DEVICE, MS5611_MEASUREMENT_RATIO, OK, ORB_ID, orb_publish(), P, perf_begin(), perf_count(), perf_end(), perf_event_count(), cdev::CDev::poll_notify(), POW2, sensor_baro_s::pressure, device::Device::read(), sensor_baro_s::temperature, and sensor_baro_s::timestamp.
Referenced by init(), read(), and Run().
|
virtual |
Reimplemented from cdev::CDev.
Definition at line 89 of file ms5611.cpp.
References _baro_topic, _class_instance, _device_type, _interface, _measure_phase, _orb_class_instance, _reports, BARO_BASE_DEVICE_PATH, collect(), sensor_baro_s::device_id, DRV_BARO_DEVTYPE_MS5607, DRV_BARO_DEVTYPE_MS5611, device::Device::external(), device::Device::get_device_id(), ToneAlarmInterface::init(), measure(), MS5607_DEVICE, MS5611_CONVERSION_INTERVAL, MS5611_DEVICE, MS56XX_DEVICE, OK, orb_advertise_multi(), ORB_ID, ORB_PRIO_DEFAULT, ORB_PRIO_HIGH, sensor_baro_s::pressure, cdev::CDev::register_class_devname(), device::Device::set_device_type(), and warnx.
Referenced by DfMS5611Wrapper::start().
|
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 from cdev::CDev.
Definition at line 278 of file ms5611.cpp.
References _measure_interval, MS5611_CONVERSION_INTERVAL, OK, SENSOR_POLLRATE_DEFAULT, SENSORIOCRESET, SENSORIOCSPOLLRATE, and start().
|
protectedvirtual |
Issue a measurement command for the current state.
Definition at line 435 of file ms5611.cpp.
References _comms_errors, _interface, _measure_perf, _measure_phase, ADDR_CMD_CONVERT_D1, ADDR_CMD_CONVERT_D2, device::Device::ioctl(), IOCTL_MEASURE, OK, perf_begin(), perf_count(), and perf_end().
Referenced by init(), read(), and Run().
void MS5611::print_info | ( | ) |
Diagnostics - print some basic information about the driver.
Definition at line 585 of file ms5611.cpp.
References _comms_errors, _device_type, _measure_interval, _reports, _sample_perf, MS5611_DEVICE, and perf_print_counter().
Referenced by ms5611::info().
|
virtual |
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 from cdev::CDev.
Definition at line 206 of file ms5611.cpp.
References _measure_interval, _measure_phase, _reports, collect(), measure(), MS5611_CONVERSION_INTERVAL, and OK.
|
overrideprotected |
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 366 of file ms5611.cpp.
References _collect_phase, _interface, _measure_interval, _measure_phase, collect(), device::Device::ioctl(), IOCTL_RESET, measure(), MS5611_CONVERSION_INTERVAL, OK, and start().
|
protected |
Initialize the automatic measurement state machine and start it.
Definition at line 348 of file ms5611.cpp.
References _collect_phase, _measure_phase, and _reports.
Referenced by ioctl(), Run(), and DfMS5611Wrapper::start().
|
protected |
Stop the automatic measurement state machine.
Definition at line 360 of file ms5611.cpp.
Referenced by DfMS5611Wrapper::stop(), and ~MS5611().
|
protected |
Definition at line 130 of file MS5611.hpp.
|
protected |
Definition at line 132 of file MS5611.hpp.
|
protected |
Definition at line 120 of file MS5611.hpp.
|
protected |
Definition at line 136 of file MS5611.hpp.
Referenced by collect(), measure(), print_info(), and ~MS5611().
|
protected |
Definition at line 119 of file MS5611.hpp.
Referenced by collect(), init(), and print_info().
|
protected |
|
protected |
Definition at line 116 of file MS5611.hpp.
Referenced by ioctl(), print_info(), read(), and Run().
|
protected |
Definition at line 135 of file MS5611.hpp.
|
protected |
|
protected |
Definition at line 125 of file MS5611.hpp.
Referenced by collect().
|
protected |
Definition at line 131 of file MS5611.hpp.
Referenced by init().
|
protected |
Definition at line 127 of file MS5611.hpp.
Referenced by collect().
|
protected |
Definition at line 114 of file MS5611.hpp.
Referenced by collect().
|
protected |
Definition at line 118 of file MS5611.hpp.
Referenced by collect(), init(), print_info(), read(), start(), and ~MS5611().
|
protected |
Definition at line 134 of file MS5611.hpp.
Referenced by collect(), print_info(), and ~MS5611().
|
protected |
Definition at line 126 of file MS5611.hpp.
Referenced by collect().
|
protected |
Definition at line 128 of file MS5611.hpp.
Referenced by collect().
|
protected |
Definition at line 124 of file MS5611.hpp.
Referenced by collect().