|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <SDP3X.hpp>
Public Member Functions | |
| SDP3X (int bus, int address=I2C_ADDRESS_1_SDP3X, const char *path=PATH_SDP3X) | |
Public Member Functions inherited from Airspeed | |
| Airspeed (int bus, int address, unsigned conversion_interval, const char *path) | |
| virtual | ~Airspeed () |
| virtual int | init () |
| virtual int | ioctl (device::file_t *filp, int cmd, unsigned long arg) |
Private Member Functions | |
| void | Run () override |
| Perform a poll cycle; collect from the previous measurement and start a new one. More... | |
| int | measure () override |
| int | collect () override |
| int | probe () override |
| bool | init_sdp3x () |
| bool | crc (const uint8_t data[], unsigned size, uint8_t checksum) |
| Calculate the CRC8 for the sensor payload data. More... | |
| int | write_command (uint16_t command) |
| Write a command in Sensirion specific logic. More... | |
Private Attributes | |
| math::LowPassFilter2p | _filter {SPD3X_MEAS_RATE, SDP3X_MEAS_DRIVER_FILTER_FREQ} |
| uint16_t | _scale {0} |
Additional Inherited Members | |
Protected Member Functions inherited from Airspeed | |
| void | start () |
| Initialise the automatic measurement state machine and start it. More... | |
| void | stop () |
| Stop the automatic measurement state machine. More... | |
| void | new_report (const differential_pressure_s &report) |
| add a new report to the reports queue More... | |
Protected Attributes inherited from Airspeed | |
| bool | _sensor_ok |
| int | _measure_interval |
| bool | _collect_phase |
| float | _diff_pres_offset |
| orb_advert_t | _airspeed_pub |
| int | _airspeed_orb_class_instance |
| int | _class_instance |
| unsigned | _conversion_interval |
| perf_counter_t | _sample_perf |
| perf_counter_t | _comms_errors |
|
inline |
|
overrideprivatevirtual |
Implements Airspeed.
Definition at line 122 of file SDP3X.cpp.
References Airspeed::_airspeed_pub, Airspeed::_comms_errors, Airspeed::_diff_pres_offset, _filter, Airspeed::_sample_perf, _scale, math::LowPassFilter2p::apply(), crc(), differential_pressure_s::device_id, differential_pressure_s::differential_pressure_filtered_pa, differential_pressure_s::differential_pressure_raw_pa, differential_pressure_s::error_count, hrt_absolute_time(), OK, ORB_ID, orb_publish(), P, perf_begin(), perf_count(), perf_end(), perf_event_count(), SDP3X_SCALE_TEMPERATURE, differential_pressure_s::temperature, and differential_pressure_s::timestamp.
Referenced by measure(), and Run().
|
private |
Calculate the CRC8 for the sensor payload data.
Definition at line 187 of file SDP3X.cpp.
Referenced by collect(), and init_sdp3x().
|
private |
Definition at line 58 of file SDP3X.cpp.
References Airspeed::_comms_errors, _scale, crc(), DRV_DIFF_PRESS_DEVTYPE_SDP31, DRV_DIFF_PRESS_DEVTYPE_SDP32, DRV_DIFF_PRESS_DEVTYPE_SDP33, perf_count(), SDP3X_CONT_MEAS_AVG_MODE, SDP3X_RESET_ADDR, SDP3X_RESET_CMD, SDP3X_SCALE_PRESSURE_SDP31, SDP3X_SCALE_PRESSURE_SDP32, SDP3X_SCALE_PRESSURE_SDP33, and write_command().
Referenced by probe().
|
inlineoverrideprivatevirtual |
|
overrideprivatevirtual |
Reimplemented from Airspeed.
Definition at line 44 of file SDP3X.cpp.
References init_sdp3x().
Referenced by measure().
|
overrideprivatevirtual |
Perform a poll cycle; collect from the previous measurement and start a new one.
Implements Airspeed.
Definition at line 171 of file SDP3X.cpp.
References Airspeed::_sensor_ok, collect(), CONVERSION_INTERVAL, and DEVICE_DEBUG.
Referenced by SDP3X().
|
private |
Write a command in Sensirion specific logic.
Definition at line 49 of file SDP3X.cpp.
Referenced by init_sdp3x().
|
private |
|
private |
Definition at line 103 of file SDP3X.hpp.
Referenced by collect(), and init_sdp3x().