PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <MS5525.hpp>
Public Member Functions | |
MS5525 (uint8_t bus, uint8_t address=I2C_ADDRESS_1_MS5525DSO, const char *path=PATH_MS5525) | |
~MS5525 () override=default | |
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 |
bool | init_ms5525 () |
uint8_t | prom_crc4 (uint16_t n_prom[]) const |
Private Attributes | |
math::LowPassFilter2p | _filter {MEAS_RATE * 0.9, MEAS_DRIVER_FILTER_FREQ} |
uint8_t | _current_cmd {CMD_CONVERT_PRES} |
unsigned | _pressure_count {0} |
uint16_t | C1 {0} |
uint16_t | C2 {0} |
uint16_t | C3 {0} |
uint16_t | C4 {0} |
uint16_t | C5 {0} |
uint16_t | C6 {0} |
int64_t | Tref {0} |
uint32_t | D1 {0} |
uint32_t | D2 {0} |
bool | _inited {false} |
Static Private Attributes | |
static constexpr uint8_t | CMD_RESET = 0x1E |
static constexpr uint8_t | CMD_ADC_READ = 0x00 |
static constexpr uint8_t | CMD_PROM_START = 0xA0 |
static constexpr uint8_t | CMD_CONVERT_PRES = 0x44 |
static constexpr uint8_t | CMD_CONVERT_TEMP = 0x54 |
static constexpr uint8_t | Q1 = 15 |
static constexpr uint8_t | Q2 = 17 |
static constexpr uint8_t | Q3 = 7 |
static constexpr uint8_t | Q4 = 5 |
static constexpr uint8_t | Q5 = 7 |
static constexpr uint8_t | Q6 = 21 |
Additional Inherited Members | |
Protected Member Functions inherited from Airspeed | |
virtual int | probe () |
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 |
Definition at line 52 of file MS5525.hpp.
|
inline |
|
overridedefault |
|
overrideprivatevirtual |
Implements Airspeed.
Definition at line 170 of file MS5525.cpp.
References Airspeed::_airspeed_pub, Airspeed::_comms_errors, _current_cmd, Airspeed::_diff_pres_offset, _filter, _pressure_count, Airspeed::_sample_perf, math::LowPassFilter2p::apply(), C1, C2, C3, C4, C6, CMD_ADC_READ, CMD_CONVERT_PRES, CMD_CONVERT_TEMP, D1, D2, hrt_absolute_time(), OK, ORB_ID, orb_publish(), P, perf_begin(), perf_count(), perf_end(), perf_event_count(), Q1, Q2, Q3, Q4, Q6, differential_pressure_s::timestamp, and Tref.
Referenced by MS5525(), and Run().
|
private |
Definition at line 62 of file MS5525.cpp.
References Airspeed::_comms_errors, C1, C2, C3, C4, C5, C6, CMD_PROM_START, CMD_RESET, DRV_DIFF_PRESS_DEVTYPE_MS5525, perf_count(), prom_crc4(), Q5, and Tref.
Referenced by measure().
|
overrideprivatevirtual |
Implements Airspeed.
Definition at line 37 of file MS5525.cpp.
References Airspeed::_comms_errors, _current_cmd, _inited, init_ms5525(), and perf_count().
Referenced by MS5525(), and Run().
|
private |
Definition at line 132 of file MS5525.cpp.
Referenced by init_ms5525().
|
overrideprivatevirtual |
Perform a poll cycle; collect from the previous measurement and start a new one.
Implements Airspeed.
Definition at line 275 of file MS5525.cpp.
References Airspeed::_collect_phase, Airspeed::_measure_interval, Airspeed::_sensor_ok, collect(), CONVERSION_INTERVAL, DEVICE_DEBUG, measure(), OK, and Airspeed::start().
Referenced by MS5525().
|
private |
Definition at line 97 of file MS5525.hpp.
|
private |
Definition at line 74 of file MS5525.hpp.
Referenced by collect().
|
private |
Definition at line 125 of file MS5525.hpp.
Referenced by measure().
|
private |
Definition at line 99 of file MS5525.hpp.
Referenced by collect().
|
private |
Definition at line 111 of file MS5525.hpp.
Referenced by collect(), and init_ms5525().
|
private |
Definition at line 112 of file MS5525.hpp.
Referenced by collect(), and init_ms5525().
|
private |
Definition at line 113 of file MS5525.hpp.
Referenced by collect(), and init_ms5525().
|
private |
Definition at line 114 of file MS5525.hpp.
Referenced by collect(), and init_ms5525().
|
private |
Definition at line 115 of file MS5525.hpp.
Referenced by init_ms5525().
|
private |
Definition at line 116 of file MS5525.hpp.
Referenced by collect(), and init_ms5525().
|
staticprivate |
Definition at line 77 of file MS5525.hpp.
Referenced by collect().
|
staticprivate |
Definition at line 87 of file MS5525.hpp.
Referenced by collect().
|
staticprivate |
Definition at line 95 of file MS5525.hpp.
Referenced by collect().
|
staticprivate |
Definition at line 79 of file MS5525.hpp.
Referenced by init_ms5525().
|
staticprivate |
Definition at line 76 of file MS5525.hpp.
Referenced by init_ms5525().
|
private |
Definition at line 121 of file MS5525.hpp.
Referenced by collect().
|
private |
Definition at line 122 of file MS5525.hpp.
Referenced by collect().
|
staticprivate |
Definition at line 103 of file MS5525.hpp.
Referenced by collect().
|
staticprivate |
Definition at line 104 of file MS5525.hpp.
Referenced by collect().
|
staticprivate |
Definition at line 105 of file MS5525.hpp.
Referenced by collect().
|
staticprivate |
Definition at line 106 of file MS5525.hpp.
Referenced by collect().
|
staticprivate |
Definition at line 107 of file MS5525.hpp.
Referenced by init_ms5525().
|
staticprivate |
Definition at line 108 of file MS5525.hpp.
Referenced by collect().
|
private |
Definition at line 118 of file MS5525.hpp.
Referenced by collect(), and init_ms5525().