PX4 Firmware
PX4 Autopilot Software http://px4.io
|
class VotedSensorsUpdate More...
#include <voted_sensors_update.h>
Classes | |
struct | SensorData |
Public Member Functions | |
VotedSensorsUpdate (const Parameters ¶meters, bool hil_enabled) | |
int | init (sensor_combined_s &raw) |
initialize subscriptions etc. More... | |
void | initializeSensors () |
This tries to find new sensor instances. More... | |
void | deinit () |
deinitialize the object (we cannot use the destructor because it is called on the wrong thread) More... | |
void | printStatus () |
void | parametersUpdate () |
call this whenever parameters got updated. More... | |
void | sensorsPoll (sensor_combined_s &raw, vehicle_air_data_s &airdata, vehicle_magnetometer_s &magnetometer) |
read new sensor data More... | |
void | setRelativeTimestamps (sensor_combined_s &raw) |
set the relative timestamps of each sensor timestamp, based on the last sensorsPoll, so that the data can be published. More... | |
void | checkFailover () |
check if a failover event occured. More... | |
int | numGyros () const |
int | gyroFd (int idx) const |
int | bestGyroFd () const |
void | calcAccelInconsistency (sensor_preflight_s &preflt) |
Calculates the magnitude in m/s/s of the largest difference between the primary and any other accel sensor. More... | |
void | calcGyroInconsistency (sensor_preflight_s &preflt) |
Calculates the magnitude in rad/s of the largest difference between the primary and any other gyro sensor. More... | |
void | calcMagInconsistency (sensor_preflight_s &preflt) |
Calculates the magnitude in Gauss of the largest difference between the primary and any other magnetometers. More... | |
Private Member Functions | |
void | initSensorClass (const orb_metadata *meta, SensorData &sensor_data, uint8_t sensor_count_max) |
void | accelPoll (sensor_combined_s &raw) |
Poll the accelerometer for updated data. More... | |
void | gyroPoll (sensor_combined_s &raw) |
Poll the gyro for updated data. More... | |
void | magPoll (vehicle_magnetometer_s &magnetometer) |
Poll the magnetometer for updated data. More... | |
void | baroPoll (vehicle_air_data_s &airdata) |
Poll the barometer for updated data. More... | |
bool | checkFailover (SensorData &sensor, const char *sensor_name, const uint64_t type) |
Check & handle failover of a sensor. More... | |
bool | applyGyroCalibration (DriverFramework::DevHandle &h, const struct gyro_calibration_s *gcal, const int device_id) |
Apply a gyro calibration. More... | |
bool | applyAccelCalibration (DriverFramework::DevHandle &h, const struct accel_calibration_s *acal, const int device_id) |
Apply a accel calibration. More... | |
bool | applyMagCalibration (DriverFramework::DevHandle &h, const struct mag_calibration_s *mcal, const int device_id) |
Apply a mag calibration. More... | |
Private Attributes | |
SensorData | _accel {} |
SensorData | _gyro {} |
SensorData | _mag {} |
SensorData | _baro {} |
orb_advert_t | _mavlink_log_pub {nullptr} |
uORB::Publication< sensor_correction_s > | _sensor_correction_pub {ORB_ID(sensor_correction)} |
handle to the sensor correction uORB topic More... | |
uORB::Publication< sensor_selection_s > | _sensor_selection_pub {ORB_ID(sensor_selection)} |
handle to the sensor selection uORB topic More... | |
sensor_combined_s | _last_sensor_data [SENSOR_COUNT_MAX] {} |
latest sensor data from all sensors instances More... | |
vehicle_air_data_s | _last_airdata [SENSOR_COUNT_MAX] {} |
latest sensor data from all sensors instances More... | |
vehicle_magnetometer_s | _last_magnetometer [SENSOR_COUNT_MAX] {} |
latest sensor data from all sensors instances More... | |
matrix::Dcmf | _board_rotation {} |
rotation matrix for the orientation that the board is mounted More... | |
matrix::Dcmf | _mag_rotation [MAG_COUNT_MAX] {} |
rotation matrix for the orientation that the external mag0 is mounted More... | |
const Parameters & | _parameters |
const bool | _hil_enabled {false} |
is hardware-in-the-loop mode enabled? More... | |
bool | _corrections_changed {false} |
bool | _selection_changed {false} |
true when a sensor selection has changed and not been published More... | |
float | _accel_diff [3][2] {} |
filtered accel differences between IMU units (m/s/s) More... | |
float | _gyro_diff [3][2] {} |
filtered gyro differences between IMU uinits (rad/s) More... | |
float | _mag_angle_diff [2] {} |
filtered mag angle differences between sensor instances (Ga) More... | |
uint32_t | _accel_device_id [SENSOR_COUNT_MAX] {} |
accel driver device id for each uorb instance More... | |
uint32_t | _baro_device_id [SENSOR_COUNT_MAX] {} |
baro driver device id for each uorb instance More... | |
uint32_t | _gyro_device_id [SENSOR_COUNT_MAX] {} |
gyro driver device id for each uorb instance More... | |
uint32_t | _mag_device_id [SENSOR_COUNT_MAX] {} |
mag driver device id for each uorb instance More... | |
uint64_t | _last_accel_timestamp [ACCEL_COUNT_MAX] {} |
latest full timestamp More... | |
sensor_correction_s | _corrections {} |
struct containing the sensor corrections to be published to the uORB More... | |
sensor_selection_s | _selection {} |
struct containing the sensor selection to be published to the uORB More... | |
subsystem_info_s | _info {} |
subsystem info publication More... | |
TemperatureCompensation | _temperature_compensation {} |
sensor thermal compensation More... | |
uORB::PublicationQueued< subsystem_info_s > | _info_pub {ORB_ID(subsystem_info)} |
class VotedSensorsUpdate
Handling of sensor updates with voting
Definition at line 78 of file voted_sensors_update.h.
VotedSensorsUpdate::VotedSensorsUpdate | ( | const Parameters & | parameters, |
bool | hil_enabled | ||
) |
parameters | parameter values. These do not have to be initialized when constructing this object. Only when calling init(), they have to be initialized. |
Definition at line 55 of file voted_sensors_update.cpp.
References _accel, _baro, _corrections, _gyro, _hil_enabled, _mag, sensor_correction_s::accel_scale_0, sensor_correction_s::accel_scale_1, sensor_correction_s::accel_scale_2, sensor_correction_s::baro_scale_0, sensor_correction_s::baro_scale_1, sensor_correction_s::baro_scale_2, sensor_correction_s::gyro_scale_0, sensor_correction_s::gyro_scale_1, sensor_correction_s::gyro_scale_2, DataValidatorGroup::set_equal_value_threshold(), DataValidatorGroup::set_timeout(), and sensors::VotedSensorsUpdate::SensorData::voter.
|
private |
Poll the accelerometer for updated data.
raw | Combined sensor data structure into which data should be returned. |
Definition at line 572 of file voted_sensors_update.cpp.
References _accel, _accel_device_id, _board_rotation, _corrections, _corrections_changed, _last_accel_timestamp, _last_sensor_data, _selection, _selection_changed, _temperature_compensation, sensor_selection_s::accel_device_id, sensor_correction_s::accel_offset_0, sensor_correction_s::accel_offset_1, sensor_correction_s::accel_offset_2, sensor_correction_s::accel_scale_0, sensor_correction_s::accel_scale_1, sensor_correction_s::accel_scale_2, sensor_combined_s::accelerometer_integral_dt, sensor_combined_s::accelerometer_m_s2, sensors::TemperatureCompensation::apply_corrections_accel(), sensor_accel_s::device_id, sensors::VotedSensorsUpdate::SensorData::enabled, sensor_accel_s::error_count, DataValidatorGroup::get_best(), hrt_absolute_time(), sensor_accel_s::integral_dt, sensors::VotedSensorsUpdate::SensorData::last_best_vote, orb_check(), orb_copy(), ORB_ID, orb_priority(), sensors::VotedSensorsUpdate::SensorData::priority, DataValidatorGroup::put(), sensor_correction_s::selected_accel_instance, sensors::VotedSensorsUpdate::SensorData::subscription, sensors::VotedSensorsUpdate::SensorData::subscription_count, sensor_accel_s::temperature, sensor_accel_s::timestamp, sensors::VotedSensorsUpdate::SensorData::voter, sensor_accel_s::x, sensor_accel_s::x_integral, sensor_accel_s::y, sensor_accel_s::y_integral, sensor_accel_s::z, and sensor_accel_s::z_integral.
Referenced by sensorsPoll().
|
private |
Apply a accel calibration.
h | reference to the DevHandle in use |
ascale | the calibration data. |
device | the device id of the sensor. |
Definition at line 1080 of file voted_sensors_update.cpp.
References ACCELIOCSSCALE.
Referenced by parametersUpdate().
|
private |
Apply a gyro calibration.
h | reference to the DevHandle in use |
gscale | the calibration data. |
device | the device id of the sensor. |
Definition at line 1066 of file voted_sensors_update.cpp.
References GYROIOCSSCALE.
Referenced by parametersUpdate().
|
private |
Apply a mag calibration.
h | reference to the DevHandle in use |
gscale | the calibration data. |
device | the device id of the sensor. |
Definition at line 1094 of file voted_sensors_update.cpp.
References MAGIOCSSCALE.
Referenced by parametersUpdate().
|
private |
Poll the barometer for updated data.
raw | Combined sensor data structure into which data should be returned. |
Definition at line 852 of file voted_sensors_update.cpp.
References _baro, _baro_device_id, _corrections, _corrections_changed, _last_airdata, _parameters, _selection, _selection_changed, _temperature_compensation, sensors::TemperatureCompensation::apply_corrections_baro(), vehicle_air_data_s::baro_alt_meter, sensor_selection_s::baro_device_id, sensor_correction_s::baro_offset_0, sensor_correction_s::baro_offset_1, sensor_correction_s::baro_offset_2, vehicle_air_data_s::baro_pressure_pa, sensors::Parameters::baro_qnh, sensor_correction_s::baro_scale_0, sensor_correction_s::baro_scale_1, sensor_correction_s::baro_scale_2, vehicle_air_data_s::baro_temp_celcius, CONSTANTS_ABSOLUTE_NULL_CELSIUS, CONSTANTS_AIR_GAS_CONST, CONSTANTS_ONE_G, sensor_baro_s::device_id, sensor_baro_s::error_count, DataValidatorGroup::get_best(), hrt_absolute_time(), sensors::VotedSensorsUpdate::SensorData::last_best_vote, orb_check(), orb_copy(), ORB_ID, orb_priority(), sensor_baro_s::pressure, sensors::VotedSensorsUpdate::SensorData::priority, DataValidatorGroup::put(), vehicle_air_data_s::rho, sensor_correction_s::selected_baro_instance, sensors::VotedSensorsUpdate::SensorData::subscription, sensors::VotedSensorsUpdate::SensorData::subscription_count, sensor_baro_s::temperature, sensor_baro_s::timestamp, vehicle_air_data_s::timestamp, and sensors::VotedSensorsUpdate::SensorData::voter.
Referenced by sensorsPoll().
|
inline |
Definition at line 131 of file voted_sensors_update.h.
References _gyro, calcAccelInconsistency(), calcGyroInconsistency(), calcMagInconsistency(), sensors::VotedSensorsUpdate::SensorData::last_best_vote, and sensors::VotedSensorsUpdate::SensorData::subscription.
Referenced by Sensors::run().
void VotedSensorsUpdate::calcAccelInconsistency | ( | sensor_preflight_s & | preflt | ) |
Calculates the magnitude in m/s/s of the largest difference between the primary and any other accel sensor.
Definition at line 1155 of file voted_sensors_update.cpp.
References _accel, _accel_diff, _last_sensor_data, sensor_preflight_s::accel_inconsistency_m_s_s, sensor_combined_s::accelerometer_m_s2, sensors::VotedSensorsUpdate::SensorData::last_best_vote, sensors::VotedSensorsUpdate::SensorData::priority, and sensors::VotedSensorsUpdate::SensorData::subscription_count.
Referenced by bestGyroFd(), and Sensors::run().
void VotedSensorsUpdate::calcGyroInconsistency | ( | sensor_preflight_s & | preflt | ) |
Calculates the magnitude in rad/s of the largest difference between the primary and any other gyro sensor.
Definition at line 1204 of file voted_sensors_update.cpp.
References _gyro, _gyro_diff, _last_sensor_data, sensor_preflight_s::gyro_inconsistency_rad_s, sensor_combined_s::gyro_rad, sensors::VotedSensorsUpdate::SensorData::last_best_vote, sensors::VotedSensorsUpdate::SensorData::priority, and sensors::VotedSensorsUpdate::SensorData::subscription_count.
Referenced by bestGyroFd(), and Sensors::run().
void VotedSensorsUpdate::calcMagInconsistency | ( | sensor_preflight_s & | preflt | ) |
Calculates the magnitude in Gauss of the largest difference between the primary and any other magnetometers.
Definition at line 1253 of file voted_sensors_update.cpp.
References _last_magnetometer, _mag, _mag_angle_diff, sensors::VotedSensorsUpdate::SensorData::last_best_vote, sensor_preflight_s::mag_inconsistency_angle, vehicle_magnetometer_s::magnetometer_ga, math::max(), sensors::VotedSensorsUpdate::SensorData::priority, and sensors::VotedSensorsUpdate::SensorData::subscription_count.
Referenced by bestGyroFd(), and Sensors::run().
void VotedSensorsUpdate::checkFailover | ( | ) |
check if a failover event occured.
if so, report it.
Definition at line 1138 of file voted_sensors_update.cpp.
References _accel, _baro, _gyro, and _mag.
Referenced by Sensors::run().
|
private |
Check & handle failover of a sensor.
Definition at line 952 of file voted_sensors_update.cpp.
References _hil_enabled, _info, _info_pub, _mavlink_log_pub, subsystem_info_s::enabled, DataValidator::ERROR_FLAG_HIGH_ERRCOUNT, DataValidator::ERROR_FLAG_HIGH_ERRDENSITY, DataValidator::ERROR_FLAG_NO_DATA, DataValidator::ERROR_FLAG_NO_ERROR, DataValidator::ERROR_FLAG_STALE_DATA, DataValidator::ERROR_FLAG_TIMEOUT, DataValidatorGroup::failover_count(), DataValidatorGroup::failover_index(), DataValidatorGroup::failover_state(), hrt_absolute_time(), sensors::VotedSensorsUpdate::SensorData::last_failover_count, mavlink_log_emergency, subsystem_info_s::ok, subsystem_info_s::present, sensors::VotedSensorsUpdate::SensorData::priority, uORB::PublicationQueued< T >::publish(), sensors::VotedSensorsUpdate::SensorData::subscription_count, subsystem_info_s::subsystem_type, subsystem_info_s::timestamp, and sensors::VotedSensorsUpdate::SensorData::voter.
void VotedSensorsUpdate::deinit | ( | ) |
deinitialize the object (we cannot use the destructor because it is called on the wrong thread)
Definition at line 102 of file voted_sensors_update.cpp.
References _accel, _baro, _gyro, _mag, orb_unsubscribe(), sensors::VotedSensorsUpdate::SensorData::subscription, and sensors::VotedSensorsUpdate::SensorData::subscription_count.
Referenced by Sensors::run().
|
inline |
Definition at line 129 of file voted_sensors_update.h.
References _gyro, and sensors::VotedSensorsUpdate::SensorData::subscription.
|
private |
Poll the gyro for updated data.
raw | Combined sensor data structure into which data should be returned. |
Definition at line 679 of file voted_sensors_update.cpp.
References _board_rotation, _corrections, _corrections_changed, _gyro, _gyro_device_id, _last_sensor_data, _selection, _selection_changed, _temperature_compensation, sensors::TemperatureCompensation::apply_corrections_gyro(), sensor_gyro_s::device_id, sensors::VotedSensorsUpdate::SensorData::enabled, sensor_gyro_s::error_count, DataValidatorGroup::get_best(), sensor_selection_s::gyro_device_id, sensor_combined_s::gyro_integral_dt, sensor_correction_s::gyro_offset_0, sensor_correction_s::gyro_offset_1, sensor_correction_s::gyro_offset_2, sensor_combined_s::gyro_rad, sensor_correction_s::gyro_scale_0, sensor_correction_s::gyro_scale_1, sensor_correction_s::gyro_scale_2, hrt_absolute_time(), sensor_gyro_s::integral_dt, sensors::VotedSensorsUpdate::SensorData::last_best_vote, orb_check(), orb_copy(), ORB_ID, orb_priority(), sensors::VotedSensorsUpdate::SensorData::priority, DataValidatorGroup::put(), sensor_correction_s::selected_gyro_instance, sensors::VotedSensorsUpdate::SensorData::subscription, sensors::VotedSensorsUpdate::SensorData::subscription_count, sensor_gyro_s::temperature, sensor_gyro_s::timestamp, sensor_combined_s::timestamp, sensors::VotedSensorsUpdate::SensorData::voter, sensor_gyro_s::x, sensor_gyro_s::x_integral, sensor_gyro_s::y, sensor_gyro_s::y_integral, sensor_gyro_s::z, and sensor_gyro_s::z_integral.
Referenced by sensorsPoll().
int VotedSensorsUpdate::init | ( | sensor_combined_s & | raw | ) |
initialize subscriptions etc.
Definition at line 81 of file voted_sensors_update.cpp.
References _corrections_changed, _selection_changed, sensor_combined_s::accelerometer_timestamp_relative, initializeSensors(), and sensor_combined_s::timestamp.
Referenced by Sensors::run().
void VotedSensorsUpdate::initializeSensors | ( | ) |
This tries to find new sensor instances.
This is called from init(), then it can be called periodically.
Definition at line 94 of file voted_sensors_update.cpp.
References _accel, _baro, _gyro, _mag, sensors::ACCEL_COUNT_MAX, sensors::BARO_COUNT_MAX, sensors::GYRO_COUNT_MAX, initSensorClass(), sensors::MAG_COUNT_MAX, and ORB_ID.
Referenced by init(), and Sensors::run().
|
private |
Definition at line 1021 of file voted_sensors_update.cpp.
References DataValidatorGroup::add_new_validator(), orb_metadata::o_name, orb_exists(), orb_subscribe_multi(), sensors::VotedSensorsUpdate::SensorData::subscription, sensors::VotedSensorsUpdate::SensorData::subscription_count, and sensors::VotedSensorsUpdate::SensorData::voter.
Referenced by initializeSensors().
|
private |
Poll the magnetometer for updated data.
raw | Combined sensor data structure into which data should be returned. |
Definition at line 787 of file voted_sensors_update.cpp.
References _last_magnetometer, _mag, _mag_device_id, _mag_rotation, _selection, _selection_changed, sensors::VotedSensorsUpdate::SensorData::enabled, DataValidatorGroup::get_best(), hrt_absolute_time(), sensors::VotedSensorsUpdate::SensorData::last_best_vote, sensor_selection_s::mag_device_id, mag_report, vehicle_magnetometer_s::magnetometer_ga, orb_check(), orb_copy(), ORB_ID, orb_priority(), parametersUpdate(), sensors::VotedSensorsUpdate::SensorData::priority, DataValidatorGroup::put(), sensors::VotedSensorsUpdate::SensorData::subscription, sensors::VotedSensorsUpdate::SensorData::subscription_count, vehicle_magnetometer_s::timestamp, and sensors::VotedSensorsUpdate::SensorData::voter.
Referenced by sensorsPoll().
|
inline |
Definition at line 127 of file voted_sensors_update.h.
References _gyro, and sensors::VotedSensorsUpdate::SensorData::subscription_count.
Referenced by Sensors::run().
void VotedSensorsUpdate::parametersUpdate | ( | ) |
call this whenever parameters got updated.
Make sure to have initializeSensors() called at least once before calling this.
Definition at line 121 of file voted_sensors_update.cpp.
References _accel, _baro, _board_rotation, _corrections, _gyro, _hil_enabled, _mag, _mag_device_id, _mag_rotation, _parameters, _temperature_compensation, ACCEL_BASE_DEVICE_PATH, sensors::ACCEL_COUNT_MAX, sensor_correction_s::accel_mapping, applyAccelCalibration(), applyGyroCalibration(), applyMagCalibration(), sensor_correction_s::baro_mapping, sensors::Parameters::board_offset, sensors::Parameters::board_rotation, CAL_ERROR_APPLY_CAL_MSG, device_id, sensors::VotedSensorsUpdate::SensorData::enabled, get_rot_matrix(), GYRO_BASE_DEVICE_PATH, sensors::GYRO_COUNT_MAX, sensor_correction_s::gyro_mapping, MAG_BASE_DEVICE_PATH, sensors::MAG_COUNT_MAX, mag_report, MAG_ROT_VAL_INTERNAL, OK, orb_copy(), ORB_ID, param_find(), param_get(), param_set(), param_set_no_notification(), sensors::TemperatureCompensation::parameters_update(), sensors::VotedSensorsUpdate::SensorData::priority, sensors::TemperatureCompensation::set_sensor_id_accel(), sensors::TemperatureCompensation::set_sensor_id_baro(), sensors::TemperatureCompensation::set_sensor_id_gyro(), sensors::VotedSensorsUpdate::SensorData::subscription, sensors::VotedSensorsUpdate::SensorData::subscription_count, gyro_calibration_s::x_offset, accel_calibration_s::x_offset, mag_calibration_s::x_offset, gyro_calibration_s::x_scale, accel_calibration_s::x_scale, mag_calibration_s::x_scale, gyro_calibration_s::y_offset, accel_calibration_s::y_offset, mag_calibration_s::y_offset, accel_calibration_s::y_scale, gyro_calibration_s::y_scale, mag_calibration_s::y_scale, gyro_calibration_s::z_offset, accel_calibration_s::z_offset, mag_calibration_s::z_offset, gyro_calibration_s::z_scale, accel_calibration_s::z_scale, and mag_calibration_s::z_scale.
Referenced by magPoll(), and Sensors::parameters_update().
void VotedSensorsUpdate::printStatus | ( | ) |
Definition at line 1051 of file voted_sensors_update.cpp.
References _accel, _baro, _gyro, _mag, _temperature_compensation, DataValidatorGroup::print(), sensors::TemperatureCompensation::print_status(), and sensors::VotedSensorsUpdate::SensorData::voter.
Referenced by Sensors::print_status().
void VotedSensorsUpdate::sensorsPoll | ( | sensor_combined_s & | raw, |
vehicle_air_data_s & | airdata, | ||
vehicle_magnetometer_s & | magnetometer | ||
) |
read new sensor data
Definition at line 1111 of file voted_sensors_update.cpp.
References _corrections, _corrections_changed, _selection, _selection_changed, _sensor_correction_pub, _sensor_selection_pub, accelPoll(), baroPoll(), gyroPoll(), hrt_absolute_time(), magPoll(), uORB::Publication< T >::publish(), sensor_correction_s::timestamp, and sensor_selection_s::timestamp.
Referenced by Sensors::run().
void VotedSensorsUpdate::setRelativeTimestamps | ( | sensor_combined_s & | raw | ) |
set the relative timestamps of each sensor timestamp, based on the last sensorsPoll, so that the data can be published.
Definition at line 1146 of file voted_sensors_update.cpp.
References _accel, _last_accel_timestamp, sensor_combined_s::accelerometer_timestamp_relative, sensors::VotedSensorsUpdate::SensorData::last_best_vote, and sensor_combined_s::timestamp.
Referenced by Sensors::run().
|
private |
Definition at line 245 of file voted_sensors_update.h.
Referenced by accelPoll(), calcAccelInconsistency(), checkFailover(), deinit(), initializeSensors(), parametersUpdate(), printStatus(), setRelativeTimestamps(), and VotedSensorsUpdate().
|
private |
accel driver device id for each uorb instance
Definition at line 272 of file voted_sensors_update.h.
Referenced by accelPoll().
|
private |
filtered accel differences between IMU units (m/s/s)
Definition at line 268 of file voted_sensors_update.h.
Referenced by calcAccelInconsistency().
|
private |
Definition at line 248 of file voted_sensors_update.h.
Referenced by baroPoll(), checkFailover(), deinit(), initializeSensors(), parametersUpdate(), printStatus(), and VotedSensorsUpdate().
|
private |
baro driver device id for each uorb instance
Definition at line 273 of file voted_sensors_update.h.
Referenced by baroPoll().
|
private |
rotation matrix for the orientation that the board is mounted
Definition at line 259 of file voted_sensors_update.h.
Referenced by accelPoll(), gyroPoll(), and parametersUpdate().
|
private |
struct containing the sensor corrections to be published to the uORB
Definition at line 279 of file voted_sensors_update.h.
Referenced by accelPoll(), baroPoll(), gyroPoll(), parametersUpdate(), sensorsPoll(), and VotedSensorsUpdate().
|
private |
Definition at line 265 of file voted_sensors_update.h.
Referenced by accelPoll(), baroPoll(), gyroPoll(), init(), and sensorsPoll().
|
private |
Definition at line 246 of file voted_sensors_update.h.
Referenced by bestGyroFd(), calcGyroInconsistency(), checkFailover(), deinit(), gyroFd(), gyroPoll(), initializeSensors(), numGyros(), parametersUpdate(), printStatus(), and VotedSensorsUpdate().
|
private |
gyro driver device id for each uorb instance
Definition at line 274 of file voted_sensors_update.h.
Referenced by gyroPoll().
|
private |
filtered gyro differences between IMU uinits (rad/s)
Definition at line 269 of file voted_sensors_update.h.
Referenced by calcGyroInconsistency().
|
private |
is hardware-in-the-loop mode enabled?
Definition at line 263 of file voted_sensors_update.h.
Referenced by checkFailover(), parametersUpdate(), and VotedSensorsUpdate().
|
private |
subsystem info publication
Definition at line 281 of file voted_sensors_update.h.
Referenced by checkFailover().
|
private |
Definition at line 285 of file voted_sensors_update.h.
Referenced by checkFailover().
|
private |
latest full timestamp
Definition at line 277 of file voted_sensors_update.h.
Referenced by accelPoll(), and setRelativeTimestamps().
|
private |
latest sensor data from all sensors instances
Definition at line 256 of file voted_sensors_update.h.
Referenced by baroPoll().
|
private |
latest sensor data from all sensors instances
Definition at line 257 of file voted_sensors_update.h.
Referenced by calcMagInconsistency(), and magPoll().
|
private |
latest sensor data from all sensors instances
Definition at line 255 of file voted_sensors_update.h.
Referenced by accelPoll(), calcAccelInconsistency(), calcGyroInconsistency(), and gyroPoll().
|
private |
Definition at line 247 of file voted_sensors_update.h.
Referenced by calcMagInconsistency(), checkFailover(), deinit(), initializeSensors(), magPoll(), parametersUpdate(), printStatus(), and VotedSensorsUpdate().
|
private |
filtered mag angle differences between sensor instances (Ga)
Definition at line 270 of file voted_sensors_update.h.
Referenced by calcMagInconsistency().
|
private |
mag driver device id for each uorb instance
Definition at line 275 of file voted_sensors_update.h.
Referenced by magPoll(), and parametersUpdate().
|
private |
rotation matrix for the orientation that the external mag0 is mounted
Definition at line 260 of file voted_sensors_update.h.
Referenced by magPoll(), and parametersUpdate().
|
private |
Definition at line 250 of file voted_sensors_update.h.
Referenced by checkFailover().
|
private |
Definition at line 262 of file voted_sensors_update.h.
Referenced by baroPoll(), and parametersUpdate().
|
private |
struct containing the sensor selection to be published to the uORB
Definition at line 280 of file voted_sensors_update.h.
Referenced by accelPoll(), baroPoll(), gyroPoll(), magPoll(), and sensorsPoll().
|
private |
true when a sensor selection has changed and not been published
Definition at line 266 of file voted_sensors_update.h.
Referenced by accelPoll(), baroPoll(), gyroPoll(), init(), magPoll(), and sensorsPoll().
|
private |
handle to the sensor correction uORB topic
Definition at line 252 of file voted_sensors_update.h.
Referenced by sensorsPoll().
|
private |
handle to the sensor selection uORB topic
Definition at line 253 of file voted_sensors_update.h.
Referenced by sensorsPoll().
|
private |
sensor thermal compensation
Definition at line 283 of file voted_sensors_update.h.
Referenced by accelPoll(), baroPoll(), gyroPoll(), parametersUpdate(), and printStatus().