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

#include <MS5525.hpp>

Inheritance diagram for MS5525:
Collaboration diagram for MS5525:

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
 

Detailed Description

Definition at line 52 of file MS5525.hpp.

Constructor & Destructor Documentation

◆ MS5525()

MS5525::MS5525 ( uint8_t  bus,
uint8_t  address = I2C_ADDRESS_1_MS5525DSO,
const char *  path = PATH_MS5525 
)
inline

Definition at line 55 of file MS5525.hpp.

References collect(), measure(), Run(), and ~MS5525().

Here is the call graph for this function:

◆ ~MS5525()

MS5525::~MS5525 ( )
overridedefault

Referenced by MS5525().

Here is the caller graph for this function:

Member Function Documentation

◆ collect()

int MS5525::collect ( )
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().

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

◆ init_ms5525()

bool MS5525::init_ms5525 ( )
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().

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

◆ measure()

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

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

◆ prom_crc4()

uint8_t MS5525::prom_crc4 ( uint16_t  n_prom[]) const
private

Definition at line 132 of file MS5525.cpp.

Referenced by init_ms5525().

Here is the caller graph for this function:

◆ Run()

void MS5525::Run ( )
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().

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

Member Data Documentation

◆ _current_cmd

uint8_t MS5525::_current_cmd {CMD_CONVERT_PRES}
private

Definition at line 97 of file MS5525.hpp.

Referenced by collect(), and measure().

◆ _filter

math::LowPassFilter2p MS5525::_filter {MEAS_RATE * 0.9, MEAS_DRIVER_FILTER_FREQ}
private

Definition at line 74 of file MS5525.hpp.

Referenced by collect().

◆ _inited

bool MS5525::_inited {false}
private

Definition at line 125 of file MS5525.hpp.

Referenced by measure().

◆ _pressure_count

unsigned MS5525::_pressure_count {0}
private

Definition at line 99 of file MS5525.hpp.

Referenced by collect().

◆ C1

uint16_t MS5525::C1 {0}
private

Definition at line 111 of file MS5525.hpp.

Referenced by collect(), and init_ms5525().

◆ C2

uint16_t MS5525::C2 {0}
private

Definition at line 112 of file MS5525.hpp.

Referenced by collect(), and init_ms5525().

◆ C3

uint16_t MS5525::C3 {0}
private

Definition at line 113 of file MS5525.hpp.

Referenced by collect(), and init_ms5525().

◆ C4

uint16_t MS5525::C4 {0}
private

Definition at line 114 of file MS5525.hpp.

Referenced by collect(), and init_ms5525().

◆ C5

uint16_t MS5525::C5 {0}
private

Definition at line 115 of file MS5525.hpp.

Referenced by init_ms5525().

◆ C6

uint16_t MS5525::C6 {0}
private

Definition at line 116 of file MS5525.hpp.

Referenced by collect(), and init_ms5525().

◆ CMD_ADC_READ

constexpr uint8_t MS5525::CMD_ADC_READ = 0x00
staticprivate

Definition at line 77 of file MS5525.hpp.

Referenced by collect().

◆ CMD_CONVERT_PRES

constexpr uint8_t MS5525::CMD_CONVERT_PRES = 0x44
staticprivate

Definition at line 87 of file MS5525.hpp.

Referenced by collect().

◆ CMD_CONVERT_TEMP

constexpr uint8_t MS5525::CMD_CONVERT_TEMP = 0x54
staticprivate

Definition at line 95 of file MS5525.hpp.

Referenced by collect().

◆ CMD_PROM_START

constexpr uint8_t MS5525::CMD_PROM_START = 0xA0
staticprivate

Definition at line 79 of file MS5525.hpp.

Referenced by init_ms5525().

◆ CMD_RESET

constexpr uint8_t MS5525::CMD_RESET = 0x1E
staticprivate

Definition at line 76 of file MS5525.hpp.

Referenced by init_ms5525().

◆ D1

uint32_t MS5525::D1 {0}
private

Definition at line 121 of file MS5525.hpp.

Referenced by collect().

◆ D2

uint32_t MS5525::D2 {0}
private

Definition at line 122 of file MS5525.hpp.

Referenced by collect().

◆ Q1

constexpr uint8_t MS5525::Q1 = 15
staticprivate

Definition at line 103 of file MS5525.hpp.

Referenced by collect().

◆ Q2

constexpr uint8_t MS5525::Q2 = 17
staticprivate

Definition at line 104 of file MS5525.hpp.

Referenced by collect().

◆ Q3

constexpr uint8_t MS5525::Q3 = 7
staticprivate

Definition at line 105 of file MS5525.hpp.

Referenced by collect().

◆ Q4

constexpr uint8_t MS5525::Q4 = 5
staticprivate

Definition at line 106 of file MS5525.hpp.

Referenced by collect().

◆ Q5

constexpr uint8_t MS5525::Q5 = 7
staticprivate

Definition at line 107 of file MS5525.hpp.

Referenced by init_ms5525().

◆ Q6

constexpr uint8_t MS5525::Q6 = 21
staticprivate

Definition at line 108 of file MS5525.hpp.

Referenced by collect().

◆ Tref

int64_t MS5525::Tref {0}
private

Definition at line 118 of file MS5525.hpp.

Referenced by collect(), and init_ms5525().


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