forked from Archive/PX4-Autopilot
sensors: uniform initialization and whitespace formatting in voted_sensors_update.h
This commit is contained in:
parent
6413525645
commit
6abf2203a3
|
@ -124,6 +124,7 @@ public:
|
|||
void checkFailover();
|
||||
|
||||
int numGyros() const { return _gyro.subscription_count; }
|
||||
|
||||
int gyroFd(int idx) const { return _gyro.subscription[idx]; }
|
||||
|
||||
int bestGyroFd() const { return _gyro.subscription[_gyro.last_best_vote]; }
|
||||
|
@ -169,39 +170,39 @@ private:
|
|||
unsigned int last_failover_count;
|
||||
};
|
||||
|
||||
void initSensorClass(const struct orb_metadata *meta, SensorData &sensor_data, uint8_t sensor_count_max);
|
||||
void initSensorClass(const orb_metadata *meta, SensorData &sensor_data, uint8_t sensor_count_max);
|
||||
|
||||
/**
|
||||
* Poll the accelerometer for updated data.
|
||||
*
|
||||
* @param raw Combined sensor data structure into which
|
||||
* data should be returned.
|
||||
* @param raw Combined sensor data structure into which
|
||||
* data should be returned.
|
||||
*/
|
||||
void accelPoll(struct sensor_combined_s &raw);
|
||||
void accelPoll(sensor_combined_s &raw);
|
||||
|
||||
/**
|
||||
* Poll the gyro for updated data.
|
||||
*
|
||||
* @param raw Combined sensor data structure into which
|
||||
* data should be returned.
|
||||
* @param raw Combined sensor data structure into which
|
||||
* data should be returned.
|
||||
*/
|
||||
void gyroPoll(struct sensor_combined_s &raw);
|
||||
void gyroPoll(sensor_combined_s &raw);
|
||||
|
||||
/**
|
||||
* Poll the magnetometer for updated data.
|
||||
*
|
||||
* @param raw Combined sensor data structure into which
|
||||
* data should be returned.
|
||||
* @param raw Combined sensor data structure into which
|
||||
* data should be returned.
|
||||
*/
|
||||
void magPoll(vehicle_magnetometer_s &magnetometer);
|
||||
void magPoll(vehicle_magnetometer_s &magnetometer);
|
||||
|
||||
/**
|
||||
* Poll the barometer for updated data.
|
||||
*
|
||||
* @param raw Combined sensor data structure into which
|
||||
* data should be returned.
|
||||
* @param raw Combined sensor data structure into which
|
||||
* data should be returned.
|
||||
*/
|
||||
void baroPoll(vehicle_air_data_s &airdata);
|
||||
void baroPoll(vehicle_air_data_s &airdata);
|
||||
|
||||
/**
|
||||
* Check & handle failover of a sensor
|
||||
|
@ -240,51 +241,47 @@ private:
|
|||
*/
|
||||
bool applyMagCalibration(DriverFramework::DevHandle &h, const struct mag_calibration_s *mcal, const int device_id);
|
||||
|
||||
SensorData _gyro;
|
||||
SensorData _accel;
|
||||
SensorData _mag;
|
||||
SensorData _baro;
|
||||
SensorData _accel {};
|
||||
SensorData _gyro {};
|
||||
SensorData _mag {};
|
||||
SensorData _baro {};
|
||||
|
||||
orb_advert_t _mavlink_log_pub = nullptr;
|
||||
orb_advert_t _mavlink_log_pub{nullptr};
|
||||
orb_advert_t _sensor_correction_pub{nullptr}; /**< handle to the sensor correction uORB topic */
|
||||
orb_advert_t _sensor_selection_pub{nullptr}; /**< handle to the sensor selection uORB topic */
|
||||
|
||||
sensor_combined_s _last_sensor_data[SENSOR_COUNT_MAX]; /**< latest sensor data from all sensors instances */
|
||||
vehicle_air_data_s _last_airdata[SENSOR_COUNT_MAX]; /**< latest sensor data from all sensors instances */
|
||||
vehicle_magnetometer_s _last_magnetometer[SENSOR_COUNT_MAX]; /**< latest sensor data from all sensors instances */
|
||||
sensor_combined_s _last_sensor_data[SENSOR_COUNT_MAX] {}; /**< latest sensor data from all sensors instances */
|
||||
vehicle_air_data_s _last_airdata[SENSOR_COUNT_MAX] {}; /**< latest sensor data from all sensors instances */
|
||||
vehicle_magnetometer_s _last_magnetometer[SENSOR_COUNT_MAX] {}; /**< latest sensor data from all sensors instances */
|
||||
|
||||
uint64_t _last_accel_timestamp[ACCEL_COUNT_MAX]; /**< latest full timestamp */
|
||||
uint64_t _last_accel_timestamp[ACCEL_COUNT_MAX] {}; /**< latest full timestamp */
|
||||
|
||||
matrix::Dcmf _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
|
||||
matrix::Dcmf _mag_rotation[MAG_COUNT_MAX]; /**< rotation matrix for the orientation that the external mag0 is mounted */
|
||||
matrix::Dcmf _board_rotation {}; /**< rotation matrix for the orientation that the board is mounted */
|
||||
matrix::Dcmf _mag_rotation[MAG_COUNT_MAX] {}; /**< rotation matrix for the orientation that the external mag0 is mounted */
|
||||
|
||||
const Parameters &_parameters;
|
||||
const bool _hil_enabled; /**< is hardware-in-the-loop mode enabled? */
|
||||
const bool _hil_enabled{false}; /**< is hardware-in-the-loop mode enabled? */
|
||||
|
||||
float _accel_diff[3][2]; /**< filtered accel differences between IMU units (m/s/s) */
|
||||
float _gyro_diff[3][2]; /**< filtered gyro differences between IMU uinits (rad/s) */
|
||||
float _mag_angle_diff[2]; /**< filtered mag angle differences between sensor instances (Ga) */
|
||||
float _accel_diff[3][2] {}; /**< filtered accel differences between IMU units (m/s/s) */
|
||||
float _gyro_diff[3][2] {}; /**< filtered gyro differences between IMU uinits (rad/s) */
|
||||
float _mag_angle_diff[2] {}; /**< filtered mag angle differences between sensor instances (Ga) */
|
||||
|
||||
/* sensor thermal compensation */
|
||||
TemperatureCompensation _temperature_compensation;
|
||||
struct sensor_correction_s _corrections; /**< struct containing the sensor corrections to be published to the uORB*/
|
||||
orb_advert_t _sensor_correction_pub = nullptr; /**< handle to the sensor correction uORB topic */
|
||||
bool _corrections_changed = false;
|
||||
TemperatureCompensation _temperature_compensation{};
|
||||
sensor_correction_s _corrections {}; /**< struct containing the sensor corrections to be published to the uORB */
|
||||
sensor_selection_s _selection {}; /**< struct containing the sensor selection to be published to the uORB */
|
||||
subsystem_info_s _info {}; /**< subsystem info publication */
|
||||
|
||||
/* sensor selection publication */
|
||||
struct sensor_selection_s _selection = {}; /**< struct containing the sensor selection to be published to the uORB*/
|
||||
orb_advert_t _sensor_selection_pub = nullptr; /**< handle to the sensor selection uORB topic */
|
||||
bool _selection_changed = false; /**< true when a sensor selection has changed and not been published */
|
||||
bool _corrections_changed{false};
|
||||
bool _selection_changed{false}; /**< true when a sensor selection has changed and not been published */
|
||||
|
||||
/* subsystem info publication */
|
||||
subsystem_info_s _info{};
|
||||
uORB::PublicationQueued<subsystem_info_s> _info_pub{ORB_ID(subsystem_info)};
|
||||
uORB::PublicationQueued<subsystem_info_s> _info_pub{ORB_ID(subsystem_info)}; /* subsystem info publication */
|
||||
|
||||
uint32_t _accel_device_id[SENSOR_COUNT_MAX] = {}; /**< accel driver device id for each uorb instance */
|
||||
uint32_t _baro_device_id[SENSOR_COUNT_MAX] = {};
|
||||
uint32_t _gyro_device_id[SENSOR_COUNT_MAX] = {};
|
||||
uint32_t _mag_device_id[SENSOR_COUNT_MAX] = {};
|
||||
uint32_t _accel_device_id[SENSOR_COUNT_MAX] {}; /**< accel driver device id for each uorb instance */
|
||||
uint32_t _baro_device_id[SENSOR_COUNT_MAX] {}; /**< baro driver device id for each uorb instance */
|
||||
uint32_t _gyro_device_id[SENSOR_COUNT_MAX] {}; /**< gyro driver device id for each uorb instance */
|
||||
uint32_t _mag_device_id[SENSOR_COUNT_MAX] {}; /**< mag driver device id for each uorb instance */
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
} /* namespace sensors */
|
||||
|
|
Loading…
Reference in New Issue