PX4 Firmware
PX4 Autopilot Software http://px4.io
|
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 Sensors * | instantiate (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... | |
Definition at line 88 of file sensors.cpp.
|
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().
|
override |
Definition at line 198 of file sensors.cpp.
References _vehicle_acceleration, _vehicle_angular_velocity, VehicleAcceleration::Stop(), and VehicleAngularVelocity::Stop().
|
private |
Do adc-related initialisation.
Definition at line 220 of file sensors.cpp.
References _hil_enabled, ADC0_DEVICE_PATH, and OK.
Referenced by run().
|
private |
Poll the ADC and update readings to suit.
raw | Combined 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().
|
static |
Definition at line 539 of file sensors.cpp.
References print_usage().
|
private |
Poll the differential pressure sensor for updated data.
raw | Combined 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().
|
static |
Definition at line 579 of file sensors.cpp.
References Sensors().
|
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().
|
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().
|
override |
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().
|
static |
Definition at line 544 of file sensors.cpp.
Referenced by custom_command().
|
override |
Definition at line 389 of file sensors.cpp.
References _airdata_pub, _armed, _loop_perf, _magnetometer_pub, _sensor_preflight, _sensor_pub, _vcontrol_mode_sub, _voted_sensors_update, adc_init(), adc_poll(), sensors::VotedSensorsUpdate::bestGyroFd(), sensors::VotedSensorsUpdate::calcAccelInconsistency(), sensors::VotedSensorsUpdate::calcGyroInconsistency(), sensors::VotedSensorsUpdate::calcMagInconsistency(), sensors::VotedSensorsUpdate::checkFailover(), uORB::Subscription::copy(), sensors::VotedSensorsUpdate::deinit(), diff_pres_poll(), hrt_absolute_time(), hrt_elapsed_time(), sensors::VotedSensorsUpdate::init(), sensors::VotedSensorsUpdate::initializeSensors(), sensors::VotedSensorsUpdate::numGyros(), parameter_update_poll(), perf_begin(), perf_end(), uORB::Publication< T >::publish(), px4_poll(), sensors::VotedSensorsUpdate::sensorsPoll(), sensors::VotedSensorsUpdate::setRelativeTimestamps(), vehicle_magnetometer_s::timestamp, sensor_preflight_s::timestamp, vehicle_air_data_s::timestamp, sensor_combined_s::timestamp, and uORB::Subscription::updated().
|
static |
Definition at line 508 of file sensors.cpp.
|
private |
attitude controls sub
Definition at line 116 of file sensors.cpp.
|
private |
|
private |
|
private |
data validator to monitor airspeed
Definition at line 129 of file sensors.cpp.
Referenced by diff_pres_poll(), print_status(), and Sensors().
|
private |
arming status of the vehicle
Definition at line 114 of file sensors.cpp.
Referenced by parameters_update(), and run().
|
private |
raw differential pressure subscription
Definition at line 117 of file sensors.cpp.
Referenced by diff_pres_poll().
|
private |
if true, HIL is active
Definition at line 113 of file sensors.cpp.
Referenced by adc_init(), and adc_poll().
|
private |
|
private |
|
private |
handles for interesting parameters
Definition at line 141 of file sensors.cpp.
Referenced by parameters_update(), and Sensors().
|
private |
notification of parameter updates
Definition at line 118 of file sensors.cpp.
Referenced by parameter_update_poll().
|
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().
|
private |
|
private |
|
private |
|
private |
Definition at line 146 of file sensors.cpp.
Referenced by print_status(), Sensors(), and ~Sensors().
|
private |
Definition at line 147 of file sensors.cpp.
Referenced by print_status(), Sensors(), and ~Sensors().
|
private |
Definition at line 143 of file sensors.cpp.
Referenced by parameters_update(), print_status(), and run().