#include <sensors.h>
|
turbomath::Vector | acc_sum_ = {0, 0, 0} |
|
float | acc_temp_sum_ = 0.0f |
|
float | accel_ [3] = {0, 0, 0} |
|
uint16_t | accel_calibration_count_ = 0 |
|
turbomath::Vector | accel_int_ |
|
bool | baro_calibrated_ = false |
|
uint16_t | baro_calibration_count_ = 0 |
|
float | baro_calibration_mean_ = 0.0f |
|
float | baro_calibration_var_ = 0.0f |
|
OutlierFilter | baro_outlier_filt_ |
|
bool | calibrating_acc_flag_ = false |
|
bool | calibrating_gyro_flag_ = false |
|
Data | data_ |
|
OutlierFilter | diff_outlier_filt_ |
|
bool | diff_pressure_calibrated_ = false |
|
uint16_t | diff_pressure_calibration_count_ = 0 |
|
float | diff_pressure_calibration_mean_ = 0.0f |
|
float | diff_pressure_calibration_var_ = 0.0f |
|
const turbomath::Vector | gravity_ = {0.0f, 0.0f, 9.80665f} |
|
float | ground_pressure_ = 0.0f |
|
float | gyro_ [3] = {0, 0, 0} |
|
uint16_t | gyro_calibration_count_ = 0 |
|
turbomath::Vector | gyro_int_ |
|
turbomath::Vector | gyro_sum_ = {0, 0, 0} |
|
bool | imu_data_sent_ |
|
uint64_t | int_start_us_ |
|
uint32_t | last_baro_cal_iter_ms_ = 0 |
|
uint32_t | last_diff_pressure_cal_iter_ms_ = 0 |
|
uint32_t | last_imu_update_ms_ = 0 |
|
uint32_t | last_time_look_for_disarmed_sensors_ = 0 |
|
turbomath::Vector | max_ = {-1000.0f, -1000.0f, -1000.0f} |
|
turbomath::Vector | min_ = {1000.0f, 1000.0f, 1000.0f} |
|
bool | new_imu_data_ |
|
uint8_t | next_sensor_to_update_ = BAROMETER |
|
uint64_t | prev_imu_read_time_us_ |
|
ROSflight & | rf_ |
|
OutlierFilter | sonar_outlier_filt_ |
|
Definition at line 120 of file sensors.h.
Enumerator |
---|
BAROMETER |
|
GNSS |
|
DIFF_PRESSURE |
|
SONAR |
|
MAGNETOMETER |
|
NUM_LOW_PRIORITY_SENSORS |
|
Definition at line 213 of file sensors.h.
rosflight_firmware::Sensors::Sensors |
( |
ROSflight & |
rosflight | ) |
|
void rosflight_firmware::Sensors::calibrate_accel |
( |
void |
| ) |
|
|
private |
void rosflight_firmware::Sensors::calibrate_baro |
( |
void |
| ) |
|
|
private |
void rosflight_firmware::Sensors::calibrate_diff_pressure |
( |
void |
| ) |
|
|
private |
void rosflight_firmware::Sensors::calibrate_gyro |
( |
void |
| ) |
|
|
private |
void rosflight_firmware::Sensors::correct_baro |
( |
void |
| ) |
|
|
private |
void rosflight_firmware::Sensors::correct_diff_pressure |
( |
void |
| ) |
|
|
private |
void rosflight_firmware::Sensors::correct_imu |
( |
void |
| ) |
|
|
private |
void rosflight_firmware::Sensors::correct_mag |
( |
void |
| ) |
|
|
private |
const Data& rosflight_firmware::Sensors::data |
( |
| ) |
const |
|
inline |
bool rosflight_firmware::Sensors::gyro_calibration_complete |
( |
void |
| ) |
|
void rosflight_firmware::Sensors::init |
( |
| ) |
|
void rosflight_firmware::Sensors::init_imu |
( |
| ) |
|
|
private |
void rosflight_firmware::Sensors::look_for_disabled_sensors |
( |
void |
| ) |
|
|
private |
void rosflight_firmware::Sensors::param_change_callback |
( |
uint16_t |
param_id | ) |
|
bool rosflight_firmware::Sensors::run |
( |
void |
| ) |
|
bool rosflight_firmware::Sensors::should_send_imu_data |
( |
void |
| ) |
|
|
inline |
bool rosflight_firmware::Sensors::start_baro_calibration |
( |
void |
| ) |
|
bool rosflight_firmware::Sensors::start_diff_pressure_calibration |
( |
void |
| ) |
|
bool rosflight_firmware::Sensors::start_gyro_calibration |
( |
void |
| ) |
|
bool rosflight_firmware::Sensors::start_imu_calibration |
( |
void |
| ) |
|
bool rosflight_firmware::Sensors::update_imu |
( |
void |
| ) |
|
|
private |
void rosflight_firmware::Sensors::update_other_sensors |
( |
void |
| ) |
|
|
private |
float rosflight_firmware::Sensors::acc_temp_sum_ = 0.0f |
|
private |
float rosflight_firmware::Sensors::accel_[3] = {0, 0, 0} |
|
private |
uint16_t rosflight_firmware::Sensors::accel_calibration_count_ = 0 |
|
private |
bool rosflight_firmware::Sensors::baro_calibrated_ = false |
|
private |
uint16_t rosflight_firmware::Sensors::baro_calibration_count_ = 0 |
|
private |
float rosflight_firmware::Sensors::baro_calibration_mean_ = 0.0f |
|
private |
float rosflight_firmware::Sensors::baro_calibration_var_ = 0.0f |
|
private |
const float rosflight_firmware::Sensors::BARO_MAX_CALIBRATION_VARIANCE = 25.0 |
|
staticprivate |
const float rosflight_firmware::Sensors::BARO_MAX_CHANGE_RATE = 200.0f |
|
staticprivate |
const float rosflight_firmware::Sensors::BARO_SAMPLE_RATE = 50.0f |
|
staticprivate |
bool rosflight_firmware::Sensors::calibrating_acc_flag_ = false |
|
private |
bool rosflight_firmware::Sensors::calibrating_gyro_flag_ = false |
|
private |
Data rosflight_firmware::Sensors::data_ |
|
private |
const float rosflight_firmware::Sensors::DIFF_MAX_CHANGE_RATE = 225.0f |
|
staticprivate |
bool rosflight_firmware::Sensors::diff_pressure_calibrated_ = false |
|
private |
uint16_t rosflight_firmware::Sensors::diff_pressure_calibration_count_ = 0 |
|
private |
float rosflight_firmware::Sensors::diff_pressure_calibration_mean_ = 0.0f |
|
private |
float rosflight_firmware::Sensors::diff_pressure_calibration_var_ = 0.0f |
|
private |
const float rosflight_firmware::Sensors::DIFF_PRESSURE_MAX_CALIBRATION_VARIANCE = 100.0 |
|
staticprivate |
const float rosflight_firmware::Sensors::DIFF_SAMPLE_RATE = 50.0f |
|
staticprivate |
const turbomath::Vector rosflight_firmware::Sensors::gravity_ = {0.0f, 0.0f, 9.80665f} |
|
private |
float rosflight_firmware::Sensors::ground_pressure_ = 0.0f |
|
private |
float rosflight_firmware::Sensors::gyro_[3] = {0, 0, 0} |
|
private |
uint16_t rosflight_firmware::Sensors::gyro_calibration_count_ = 0 |
|
private |
bool rosflight_firmware::Sensors::imu_data_sent_ |
|
private |
uint64_t rosflight_firmware::Sensors::int_start_us_ |
|
private |
uint32_t rosflight_firmware::Sensors::last_baro_cal_iter_ms_ = 0 |
|
private |
uint32_t rosflight_firmware::Sensors::last_diff_pressure_cal_iter_ms_ = 0 |
|
private |
uint32_t rosflight_firmware::Sensors::last_imu_update_ms_ = 0 |
|
private |
uint32_t rosflight_firmware::Sensors::last_time_look_for_disarmed_sensors_ = 0 |
|
private |
bool rosflight_firmware::Sensors::new_imu_data_ |
|
private |
uint8_t rosflight_firmware::Sensors::next_sensor_to_update_ = BAROMETER |
|
private |
uint64_t rosflight_firmware::Sensors::prev_imu_read_time_us_ |
|
private |
const int rosflight_firmware::Sensors::SENSOR_CAL_CYCLES = 127 |
|
staticprivate |
const int rosflight_firmware::Sensors::SENSOR_CAL_DELAY_CYCLES = 128 |
|
staticprivate |
const float rosflight_firmware::Sensors::SONAR_MAX_CHANGE_RATE = 100.0f |
|
staticprivate |
const float rosflight_firmware::Sensors::SONAR_SAMPLE_RATE = 50.0f |
|
staticprivate |
The documentation for this class was generated from the following files: