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

Public Member Functions

 Sensors (bool hil_enabled)
 
 ~Sensors () override
 
void run () override
 
int print_status () override
 

Static Public Member Functions

static int task_spawn (int argc, char *argv[])
 
static Sensorsinstantiate (int argc, char *argv[])
 
static int custom_command (int argc, char *argv[])
 
static int print_usage (const char *reason=nullptr)
 

Private Member Functions

int parameters_update ()
 Update our local parameter cache. More...
 
void diff_pres_poll (const vehicle_air_data_s &airdata)
 Poll the differential pressure sensor for updated data. More...
 
void parameter_update_poll (bool forced=false)
 Check for changes in parameters. More...
 
int adc_init ()
 Do adc-related initialisation. More...
 
void adc_poll ()
 Poll the ADC and update readings to suit. More...
 

Private Attributes

const bool _hil_enabled
 if true, HIL is active More...
 
bool _armed {false}
 arming status of the vehicle More...
 
uORB::Subscription _actuator_ctrl_0_sub {ORB_ID(actuator_controls_0)}
 attitude controls sub More...
 
uORB::Subscription _diff_pres_sub {ORB_ID(differential_pressure)}
 raw differential pressure subscription More...
 
uORB::Subscription _parameter_update_sub {ORB_ID(parameter_update)}
 notification of parameter updates More...
 
uORB::Subscription _vcontrol_mode_sub {ORB_ID(vehicle_control_mode)}
 vehicle control mode subscription More...
 
uORB::Publication< airspeed_s_airspeed_pub {ORB_ID(airspeed)}
 airspeed More...
 
uORB::Publication< sensor_combined_s_sensor_pub {ORB_ID(sensor_combined)}
 combined sensor data topic More...
 
uORB::Publication< sensor_preflight_s_sensor_preflight {ORB_ID(sensor_preflight)}
 sensor preflight topic More...
 
uORB::Publication< vehicle_air_data_s_airdata_pub {ORB_ID(vehicle_air_data)}
 combined sensor data topic More...
 
uORB::Publication< vehicle_magnetometer_s_magnetometer_pub {ORB_ID(vehicle_magnetometer)}
 combined sensor data topic More...
 
perf_counter_t _loop_perf
 loop performance counter More...
 
DataValidator _airspeed_validator
 data validator to monitor airspeed More...
 
Parameters _parameters {}
 local copies of interesting parameters More...
 
ParameterHandles _parameter_handles {}
 handles for interesting parameters More...
 
VotedSensorsUpdate _voted_sensors_update
 
VehicleAcceleration _vehicle_acceleration
 
VehicleAngularVelocity _vehicle_angular_velocity
 

Detailed Description

Definition at line 88 of file sensors.cpp.

Constructor & Destructor Documentation

◆ Sensors()

Sensors::Sensors ( bool  hil_enabled)
explicit

Definition at line 183 of file sensors.cpp.

References _airspeed_validator, _parameter_handles, _vehicle_acceleration, _vehicle_angular_velocity, battery_status::initialize_parameter_handles(), DataValidator::set_equal_value_threshold(), DataValidator::set_timeout(), VehicleAcceleration::Start(), and VehicleAngularVelocity::Start().

Referenced by instantiate().

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

◆ ~Sensors()

Sensors::~Sensors ( )
override

Definition at line 198 of file sensors.cpp.

References _vehicle_acceleration, _vehicle_angular_velocity, VehicleAcceleration::Stop(), and VehicleAngularVelocity::Stop().

Here is the call graph for this function:

Member Function Documentation

◆ adc_init()

int Sensors::adc_init ( )
private

Do adc-related initialisation.

Definition at line 220 of file sensors.cpp.

References _hil_enabled, ADC0_DEVICE_PATH, and OK.

Referenced by run().

Here is the caller graph for this function:

◆ adc_poll()

void Sensors::adc_poll ( )
private

Poll the ADC and update readings to suit.

Parameters
rawCombined sensor data structure into which data should be returned.

Definition at line 332 of file sensors.cpp.

References _hil_enabled, _parameters, sensors::Parameters::diff_pres_offset_pa, f(), hrt_absolute_time(), hrt_abstime, px4_adc_msg_t, and PX4_MAX_ADC_CHANNELS.

Referenced by run().

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

◆ custom_command()

int Sensors::custom_command ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 539 of file sensors.cpp.

References print_usage().

Here is the call graph for this function:

◆ diff_pres_poll()

void Sensors::diff_pres_poll ( const vehicle_air_data_s airdata)
private

Poll the differential pressure sensor for updated data.

Parameters
rawCombined sensor data structure into which data should be returned.

Definition at line 242 of file sensors.cpp.

References _airspeed_pub, _airspeed_validator, _diff_pres_sub, _parameters, sensors::Parameters::air_cmodel, airspeed_s::air_temperature_celsius, sensors::Parameters::air_tube_diameter_mm, sensors::Parameters::air_tube_length, AIRSPEED_SENSOR_MODEL_MEMBRANE, AIRSPEED_SENSOR_MODEL_SDP3X, vehicle_air_data_s::baro_pressure_pa, vehicle_air_data_s::baro_temp_celcius, calc_IAS_corrected(), calc_TAS_from_EAS(), airspeed_s::confidence, DataValidator::confidence(), DRV_DIFF_PRESS_DEVTYPE_SDP31, DRV_DIFF_PRESS_DEVTYPE_SDP32, DRV_DIFF_PRESS_DEVTYPE_SDP33, hrt_absolute_time(), airspeed_s::indicated_airspeed_m_s, ORB_PRIO_HIGH, PCB_TEMP_ESTIMATE_DEG, uORB::Publication< T >::publish(), DataValidator::put(), differential_pressure_s::temperature, airspeed_s::timestamp, airspeed_s::true_airspeed_m_s, and uORB::Subscription::update().

Referenced by run().

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

◆ instantiate()

Sensors * Sensors::instantiate ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 579 of file sensors.cpp.

References Sensors().

Here is the call graph for this function:

◆ parameter_update_poll()

void Sensors::parameter_update_poll ( bool  forced = false)
private

Check for changes in parameters.

Definition at line 300 of file sensors.cpp.

References _parameter_update_sub, _parameters, AIRSPEED0_DEVICE_PATH, AIRSPEEDIOCSSCALE, uORB::Subscription::copy(), sensors::Parameters::diff_pres_offset_pa, fd, OK, parameters_update(), px4_close(), px4_ioctl(), px4_open(), uORB::Subscription::updated(), and warn.

Referenced by run().

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

◆ parameters_update()

int Sensors::parameters_update ( )
private

Update our local parameter cache.

Definition at line 205 of file sensors.cpp.

References _armed, _parameter_handles, _parameters, _voted_sensors_update, sensors::VotedSensorsUpdate::parametersUpdate(), and battery_status::update_parameters().

Referenced by parameter_update_poll().

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

◆ print_status()

int Sensors::print_status ( )
override
See also
ModuleBase::print_status()

Definition at line 526 of file sensors.cpp.

References _airspeed_validator, _vehicle_acceleration, _vehicle_angular_velocity, _voted_sensors_update, DataValidator::print(), VehicleAcceleration::PrintStatus(), VehicleAngularVelocity::PrintStatus(), and sensors::VotedSensorsUpdate::printStatus().

Here is the call graph for this function:

◆ print_usage()

int Sensors::print_usage ( const char *  reason = nullptr)
static
See also
ModuleBase

Definition at line 544 of file sensors.cpp.

Referenced by custom_command().

Here is the caller graph for this function:

◆ run()

◆ task_spawn()

int Sensors::task_spawn ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 508 of file sensors.cpp.

Member Data Documentation

◆ _actuator_ctrl_0_sub

uORB::Subscription Sensors::_actuator_ctrl_0_sub {ORB_ID(actuator_controls_0)}
private

attitude controls sub

Definition at line 116 of file sensors.cpp.

◆ _airdata_pub

uORB::Publication<vehicle_air_data_s> Sensors::_airdata_pub {ORB_ID(vehicle_air_data)}
private

combined sensor data topic

Definition at line 124 of file sensors.cpp.

Referenced by run().

◆ _airspeed_pub

uORB::Publication<airspeed_s> Sensors::_airspeed_pub {ORB_ID(airspeed)}
private

airspeed

Definition at line 121 of file sensors.cpp.

Referenced by diff_pres_poll().

◆ _airspeed_validator

DataValidator Sensors::_airspeed_validator
private

data validator to monitor airspeed

Definition at line 129 of file sensors.cpp.

Referenced by diff_pres_poll(), print_status(), and Sensors().

◆ _armed

bool Sensors::_armed {false}
private

arming status of the vehicle

Definition at line 114 of file sensors.cpp.

Referenced by parameters_update(), and run().

◆ _diff_pres_sub

uORB::Subscription Sensors::_diff_pres_sub {ORB_ID(differential_pressure)}
private

raw differential pressure subscription

Definition at line 117 of file sensors.cpp.

Referenced by diff_pres_poll().

◆ _hil_enabled

const bool Sensors::_hil_enabled
private

if true, HIL is active

Definition at line 113 of file sensors.cpp.

Referenced by adc_init(), and adc_poll().

◆ _loop_perf

perf_counter_t Sensors::_loop_perf
private

loop performance counter

Definition at line 127 of file sensors.cpp.

Referenced by run().

◆ _magnetometer_pub

uORB::Publication<vehicle_magnetometer_s> Sensors::_magnetometer_pub {ORB_ID(vehicle_magnetometer)}
private

combined sensor data topic

Definition at line 125 of file sensors.cpp.

Referenced by run().

◆ _parameter_handles

ParameterHandles Sensors::_parameter_handles {}
private

handles for interesting parameters

Definition at line 141 of file sensors.cpp.

Referenced by parameters_update(), and Sensors().

◆ _parameter_update_sub

uORB::Subscription Sensors::_parameter_update_sub {ORB_ID(parameter_update)}
private

notification of parameter updates

Definition at line 118 of file sensors.cpp.

Referenced by parameter_update_poll().

◆ _parameters

Parameters Sensors::_parameters {}
private

local copies of interesting parameters

Definition at line 140 of file sensors.cpp.

Referenced by adc_poll(), diff_pres_poll(), parameter_update_poll(), and parameters_update().

◆ _sensor_preflight

uORB::Publication<sensor_preflight_s> Sensors::_sensor_preflight {ORB_ID(sensor_preflight)}
private

sensor preflight topic

Definition at line 123 of file sensors.cpp.

Referenced by run().

◆ _sensor_pub

uORB::Publication<sensor_combined_s> Sensors::_sensor_pub {ORB_ID(sensor_combined)}
private

combined sensor data topic

Definition at line 122 of file sensors.cpp.

Referenced by run().

◆ _vcontrol_mode_sub

uORB::Subscription Sensors::_vcontrol_mode_sub {ORB_ID(vehicle_control_mode)}
private

vehicle control mode subscription

Definition at line 119 of file sensors.cpp.

Referenced by run().

◆ _vehicle_acceleration

VehicleAcceleration Sensors::_vehicle_acceleration
private

Definition at line 146 of file sensors.cpp.

Referenced by print_status(), Sensors(), and ~Sensors().

◆ _vehicle_angular_velocity

VehicleAngularVelocity Sensors::_vehicle_angular_velocity
private

Definition at line 147 of file sensors.cpp.

Referenced by print_status(), Sensors(), and ~Sensors().

◆ _voted_sensors_update

VotedSensorsUpdate Sensors::_voted_sensors_update
private

Definition at line 143 of file sensors.cpp.

Referenced by parameters_update(), print_status(), and run().


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