PX4 Firmware
PX4 Autopilot Software http://px4.io
MEASAirspeed Class Reference
Inheritance diagram for MEASAirspeed:
Collaboration diagram for MEASAirspeed:

Public Member Functions

 MEASAirspeed (int bus, int address=I2C_ADDRESS_MS4525DO, const char *path=PATH_MS4525)
 
- 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)
 

Protected 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
 
void voltage_correction (float &diff_pres_pa, float &temperature)
 Correct for 5V rail voltage variations. More...
 
- 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

math::LowPassFilter2p _filter {MEAS_RATE, MEAS_DRIVER_FILTER_FREQ}
 
int _t_system_power {-1}
 
system_power_s system_power {}
 
- 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 77 of file ms4525_airspeed.cpp.

Constructor & Destructor Documentation

◆ MEASAirspeed()

MEASAirspeed::MEASAirspeed ( int  bus,
int  address = I2C_ADDRESS_MS4525DO,
const char *  path = PATH_MS4525 
)

Definition at line 108 of file ms4525_airspeed.cpp.

References DRV_DIFF_PRESS_DEVTYPE_MS4525.

Referenced by meas_airspeed::start_bus().

Here is the caller graph for this function:

Member Function Documentation

◆ collect()

int MEASAirspeed::collect ( )
overrideprotectedvirtual

Implements Airspeed.

Definition at line 128 of file ms4525_airspeed.cpp.

References Airspeed::_airspeed_pub, Airspeed::_comms_errors, Airspeed::_diff_pres_offset, _filter, Airspeed::_sample_perf, math::LowPassFilter2p::apply(), 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(), perf_begin(), perf_count(), perf_end(), perf_event_count(), status, differential_pressure_s::temperature, differential_pressure_s::timestamp, and voltage_correction().

Referenced by Run().

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

◆ measure()

int MEASAirspeed::measure ( )
overrideprotectedvirtual

Implements Airspeed.

Definition at line 114 of file ms4525_airspeed.cpp.

References Airspeed::_comms_errors, OK, and perf_count().

Referenced by Run().

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

◆ Run()

void MEASAirspeed::Run ( )
overrideprotectedvirtual

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

Implements Airspeed.

Definition at line 227 of file ms4525_airspeed.cpp.

References Airspeed::_collect_phase, Airspeed::_measure_interval, Airspeed::_sensor_ok, collect(), CONVERSION_INTERVAL, DEVICE_DEBUG, measure(), OK, and Airspeed::start().

Here is the call graph for this function:

◆ voltage_correction()

void MEASAirspeed::voltage_correction ( float &  diff_press_pa,
float &  temperature 
)
protected

Correct for 5V rail voltage variations.

correct for 5V rail voltage if the system_power ORB topic is available

See http://uav.tridgell.net/MS4525/MS4525-offset.png for a graph of offset versus voltage for 3 sensors

Definition at line 283 of file ms4525_airspeed.cpp.

References _t_system_power, f(), orb_check(), orb_copy(), ORB_ID, orb_subscribe(), system_power, and system_power_s::voltage5v_v.

Referenced by collect().

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

Member Data Documentation

◆ _filter

math::LowPassFilter2p MEASAirspeed::_filter {MEAS_RATE, MEAS_DRIVER_FILTER_FREQ}
protected

Definition at line 92 of file ms4525_airspeed.cpp.

Referenced by collect().

◆ _t_system_power

int MEASAirspeed::_t_system_power {-1}
protected

Definition at line 99 of file ms4525_airspeed.cpp.

Referenced by voltage_correction().

◆ system_power

system_power_s MEASAirspeed::system_power {}
protected

Definition at line 100 of file ms4525_airspeed.cpp.

Referenced by voltage_correction().


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