2021-11-25 16:05:40 -04:00
|
|
|
#define AP_INLINE_VECTOR_OPS
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2023-07-13 21:58:06 -03:00
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
2014-10-14 01:48:33 -03:00
|
|
|
#include "AP_InertialSensor.h"
|
|
|
|
#include "AP_InertialSensor_Backend.h"
|
2019-01-18 00:23:42 -04:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
2019-11-01 23:32:59 -03:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2018-02-09 04:10:30 -04:00
|
|
|
#if AP_MODULE_SUPPORTED
|
2016-07-12 08:50:46 -03:00
|
|
|
#include <AP_Module/AP_Module.h>
|
2018-02-09 04:10:30 -04:00
|
|
|
#endif
|
2021-12-13 22:44:21 -04:00
|
|
|
#include <stdio.h>
|
2017-04-30 21:53:41 -03:00
|
|
|
|
|
|
|
#define SENSOR_RATE_DEBUG 0
|
2014-10-14 01:48:33 -03:00
|
|
|
|
2023-03-03 16:42:21 -04:00
|
|
|
#ifndef AP_HEATER_IMU_INSTANCE
|
|
|
|
#define AP_HEATER_IMU_INSTANCE 0
|
|
|
|
#endif
|
|
|
|
|
2015-11-15 20:05:20 -04:00
|
|
|
const extern AP_HAL::HAL& hal;
|
|
|
|
|
2014-10-15 05:54:30 -03:00
|
|
|
AP_InertialSensor_Backend::AP_InertialSensor_Backend(AP_InertialSensor &imu) :
|
2016-09-03 12:37:47 -03:00
|
|
|
_imu(imu)
|
2016-11-03 21:06:19 -03:00
|
|
|
{
|
|
|
|
}
|
2014-10-14 01:48:33 -03:00
|
|
|
|
2017-04-30 21:53:41 -03:00
|
|
|
/*
|
|
|
|
notify of a FIFO reset so we don't use bad data to update observed sensor rate
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::notify_accel_fifo_reset(uint8_t instance)
|
|
|
|
{
|
|
|
|
_imu._sample_accel_count[instance] = 0;
|
|
|
|
_imu._sample_accel_start_us[instance] = 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
notify of a FIFO reset so we don't use bad data to update observed sensor rate
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::notify_gyro_fifo_reset(uint8_t instance)
|
|
|
|
{
|
|
|
|
_imu._sample_gyro_count[instance] = 0;
|
|
|
|
_imu._sample_gyro_start_us[instance] = 0;
|
|
|
|
}
|
|
|
|
|
2017-05-01 00:01:43 -03:00
|
|
|
// set the amount of oversamping a accel is doing
|
|
|
|
void AP_InertialSensor_Backend::_set_accel_oversampling(uint8_t instance, uint8_t n)
|
|
|
|
{
|
|
|
|
_imu._accel_over_sampling[instance] = n;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set the amount of oversamping a gyro is doing
|
|
|
|
void AP_InertialSensor_Backend::_set_gyro_oversampling(uint8_t instance, uint8_t n)
|
|
|
|
{
|
|
|
|
_imu._gyro_over_sampling[instance] = n;
|
|
|
|
}
|
|
|
|
|
2017-04-30 21:53:41 -03:00
|
|
|
/*
|
|
|
|
update the sensor rate for FIFO sensors
|
|
|
|
|
|
|
|
FIFO sensors produce samples at a fixed rate, but the clock in the
|
|
|
|
sensor may vary slightly from the system clock. This slowly adjusts
|
|
|
|
the rate to the observed rate
|
|
|
|
*/
|
2018-03-18 20:28:33 -03:00
|
|
|
void AP_InertialSensor_Backend::_update_sensor_rate(uint16_t &count, uint32_t &start_us, float &rate_hz) const
|
2017-04-30 21:53:41 -03:00
|
|
|
{
|
|
|
|
uint32_t now = AP_HAL::micros();
|
|
|
|
if (start_us == 0) {
|
|
|
|
count = 0;
|
|
|
|
start_us = now;
|
|
|
|
} else {
|
|
|
|
count++;
|
|
|
|
if (now - start_us > 1000000UL) {
|
2019-04-04 19:07:44 -03:00
|
|
|
float observed_rate_hz = count * 1.0e6f / (now - start_us);
|
2020-04-20 19:34:47 -03:00
|
|
|
#if 0
|
|
|
|
printf("IMU RATE: %.1f should be %.1f\n", observed_rate_hz, rate_hz);
|
2017-04-30 21:53:41 -03:00
|
|
|
#endif
|
2019-04-04 19:07:44 -03:00
|
|
|
float filter_constant = 0.98f;
|
|
|
|
float upper_limit = 1.05f;
|
|
|
|
float lower_limit = 0.95f;
|
2019-08-30 04:33:42 -03:00
|
|
|
if (sensors_converging()) {
|
2017-05-01 00:15:41 -03:00
|
|
|
// converge quickly for first 30s, then more slowly
|
2019-04-04 19:07:44 -03:00
|
|
|
filter_constant = 0.8f;
|
|
|
|
upper_limit = 2.0f;
|
|
|
|
lower_limit = 0.5f;
|
2017-05-01 00:15:41 -03:00
|
|
|
}
|
|
|
|
observed_rate_hz = constrain_float(observed_rate_hz, rate_hz*lower_limit, rate_hz*upper_limit);
|
|
|
|
rate_hz = filter_constant * rate_hz + (1-filter_constant) * observed_rate_hz;
|
2017-04-30 21:53:41 -03:00
|
|
|
count = 0;
|
|
|
|
start_us = now;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-03-10 04:05:41 -03:00
|
|
|
void AP_InertialSensor_Backend::_rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
|
|
|
|
{
|
|
|
|
/*
|
2015-03-11 20:22:52 -03:00
|
|
|
accel calibration is always done in sensor frame with this
|
|
|
|
version of the code. That means we apply the rotation after the
|
|
|
|
offsets and scaling.
|
2015-03-10 04:05:41 -03:00
|
|
|
*/
|
|
|
|
|
2016-11-03 06:19:04 -03:00
|
|
|
// rotate for sensor orientation
|
|
|
|
accel.rotate(_imu._accel_orientation[instance]);
|
2015-07-22 15:19:31 -03:00
|
|
|
|
2021-01-09 01:23:18 -04:00
|
|
|
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|
2021-01-15 21:23:17 -04:00
|
|
|
if (_imu.tcal_learning) {
|
2023-02-17 00:26:27 -04:00
|
|
|
_imu.tcal(instance).update_accel_learning(accel, _imu.get_temperature(instance));
|
2021-01-15 21:23:17 -04:00
|
|
|
}
|
2021-01-09 01:23:18 -04:00
|
|
|
#endif
|
|
|
|
|
2021-05-17 14:44:53 -03:00
|
|
|
if (!_imu._calibrating_accel && (_imu._acal == nullptr
|
|
|
|
#if HAL_INS_ACCELCAL_ENABLED
|
|
|
|
|| !_imu._acal->running()
|
|
|
|
#endif
|
|
|
|
)) {
|
2021-01-07 20:46:35 -04:00
|
|
|
|
|
|
|
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|
|
|
|
// apply temperature corrections
|
2023-02-17 00:26:27 -04:00
|
|
|
_imu.tcal(instance).correct_accel(_imu.get_temperature(instance), _imu.caltemp_accel(instance), accel);
|
2021-01-07 20:46:35 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// apply offsets
|
2023-02-17 00:26:27 -04:00
|
|
|
accel -= _imu._accel_offset(instance);
|
2021-01-07 20:46:35 -04:00
|
|
|
|
|
|
|
|
|
|
|
// apply scaling
|
2023-02-17 00:26:27 -04:00
|
|
|
const Vector3f &accel_scale = _imu._accel_scale(instance).get();
|
2021-01-07 20:46:35 -04:00
|
|
|
accel.x *= accel_scale.x;
|
|
|
|
accel.y *= accel_scale.y;
|
|
|
|
accel.z *= accel_scale.z;
|
|
|
|
}
|
2015-03-10 04:05:41 -03:00
|
|
|
|
2015-03-11 20:22:52 -03:00
|
|
|
// rotate to body frame
|
2021-11-05 13:11:46 -03:00
|
|
|
accel.rotate(_imu._board_orientation);
|
2015-02-17 02:54:17 -04:00
|
|
|
}
|
|
|
|
|
2015-03-10 04:05:41 -03:00
|
|
|
void AP_InertialSensor_Backend::_rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
|
|
|
|
{
|
2016-11-03 06:19:04 -03:00
|
|
|
// rotate for sensor orientation
|
|
|
|
gyro.rotate(_imu._gyro_orientation[instance]);
|
2021-01-09 01:23:18 -04:00
|
|
|
|
|
|
|
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|
2021-01-15 21:23:17 -04:00
|
|
|
if (_imu.tcal_learning) {
|
2023-02-17 00:26:27 -04:00
|
|
|
_imu.tcal(instance).update_gyro_learning(gyro, _imu.get_temperature(instance));
|
2021-01-15 21:23:17 -04:00
|
|
|
}
|
2021-01-09 01:23:18 -04:00
|
|
|
#endif
|
2016-11-03 06:19:04 -03:00
|
|
|
|
2021-01-07 20:46:35 -04:00
|
|
|
if (!_imu._calibrating_gyro) {
|
|
|
|
|
|
|
|
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|
|
|
|
// apply temperature corrections
|
2023-02-17 00:26:27 -04:00
|
|
|
_imu.tcal(instance).correct_gyro(_imu.get_temperature(instance), _imu.caltemp_gyro(instance), gyro);
|
2021-01-07 20:46:35 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// gyro calibration is always assumed to have been done in sensor frame
|
2023-02-17 00:26:27 -04:00
|
|
|
gyro -= _imu._gyro_offset(instance);
|
2021-01-07 20:46:35 -04:00
|
|
|
}
|
2016-11-03 06:19:04 -03:00
|
|
|
|
2021-11-05 13:11:46 -03:00
|
|
|
gyro.rotate(_imu._board_orientation);
|
2015-02-17 02:54:17 -04:00
|
|
|
}
|
|
|
|
|
2014-10-14 01:48:33 -03:00
|
|
|
/*
|
|
|
|
rotate gyro vector and add the gyro offset
|
|
|
|
*/
|
2021-09-14 17:28:20 -03:00
|
|
|
void AP_InertialSensor_Backend::_publish_gyro(uint8_t instance, const Vector3f &gyro) /* front end */
|
2014-10-14 01:48:33 -03:00
|
|
|
{
|
2024-07-09 08:30:23 -03:00
|
|
|
if (has_been_killed(instance)) {
|
2019-04-18 01:24:01 -03:00
|
|
|
return;
|
|
|
|
}
|
2014-10-15 05:54:30 -03:00
|
|
|
_imu._gyro[instance] = gyro;
|
2014-10-15 23:27:22 -03:00
|
|
|
_imu._gyro_healthy[instance] = true;
|
2015-09-10 09:34:01 -03:00
|
|
|
|
|
|
|
// publish delta angle
|
|
|
|
_imu._delta_angle[instance] = _imu._delta_angle_acc[instance];
|
2016-01-16 00:41:19 -04:00
|
|
|
_imu._delta_angle_dt[instance] = _imu._delta_angle_acc_dt[instance];
|
2015-09-10 09:34:01 -03:00
|
|
|
_imu._delta_angle_valid[instance] = true;
|
2021-08-30 03:47:54 -03:00
|
|
|
|
|
|
|
_imu._delta_angle_acc[instance].zero();
|
|
|
|
_imu._delta_angle_acc_dt[instance] = 0;
|
2015-02-17 02:54:17 -04:00
|
|
|
}
|
|
|
|
|
2022-09-22 11:35:48 -03:00
|
|
|
|
|
|
|
void AP_InertialSensor_Backend::save_gyro_window(const uint8_t instance, const Vector3f &gyro, uint8_t phase)
|
|
|
|
{
|
2022-11-28 05:33:50 -04:00
|
|
|
#if HAL_GYROFFT_ENABLED
|
2022-09-22 11:35:48 -03:00
|
|
|
// capture gyro window for FFT analysis
|
|
|
|
if (_imu._fft_window_phase == phase) {
|
|
|
|
if (_imu._gyro_window_size > 0) {
|
|
|
|
Vector3f scaled_gyro = gyro * _imu._gyro_raw_sampling_multiplier[instance];
|
|
|
|
// LPF always must come last to remove high-frequency shot noise, but the FFT still
|
|
|
|
// needs to see the same data so gets its own LPF at the tap point
|
|
|
|
if (_imu._post_filter_fft) {
|
|
|
|
scaled_gyro = _imu._post_filter_gyro_filter[instance].apply(scaled_gyro);
|
|
|
|
}
|
|
|
|
_imu._gyro_window[instance][0].push(scaled_gyro.x);
|
|
|
|
_imu._gyro_window[instance][1].push(scaled_gyro.y);
|
|
|
|
_imu._gyro_window[instance][2].push(scaled_gyro.z);
|
|
|
|
_imu._last_gyro_for_fft[instance] = scaled_gyro;
|
|
|
|
} else {
|
|
|
|
_imu._last_gyro_for_fft[instance] = gyro * _imu._gyro_raw_sampling_multiplier[instance];;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2022-02-17 01:43:09 -04:00
|
|
|
/*
|
|
|
|
apply harmonic notch and low pass gyro filters
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::apply_gyro_filters(const uint8_t instance, const Vector3f &gyro)
|
|
|
|
{
|
2022-09-22 11:35:48 -03:00
|
|
|
uint8_t filter_phase = 0;
|
|
|
|
save_gyro_window(instance, gyro, filter_phase++);
|
|
|
|
|
2022-02-17 01:43:09 -04:00
|
|
|
Vector3f gyro_filtered = gyro;
|
|
|
|
|
2024-02-12 20:26:07 -04:00
|
|
|
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
2022-02-17 01:43:09 -04:00
|
|
|
// apply the harmonic notch filters
|
|
|
|
for (auto ¬ch : _imu.harmonic_notches) {
|
|
|
|
if (!notch.params.enabled()) {
|
|
|
|
continue;
|
|
|
|
}
|
2022-06-11 23:32:46 -03:00
|
|
|
bool inactive = notch.is_inactive();
|
2024-01-10 18:16:57 -04:00
|
|
|
#if AP_AHRS_ENABLED
|
2022-02-17 01:43:09 -04:00
|
|
|
// by default we only run the expensive notch filters on the
|
|
|
|
// currently active IMU we reset the inactive notch filters so
|
|
|
|
// that if we switch IMUs we're not left with old data
|
|
|
|
if (!notch.params.hasOption(HarmonicNotchFilterParams::Options::EnableOnAllIMUs) &&
|
|
|
|
instance != AP::ahrs().get_primary_gyro_index()) {
|
2022-06-11 23:32:46 -03:00
|
|
|
inactive = true;
|
2022-02-17 01:43:09 -04:00
|
|
|
}
|
|
|
|
#endif
|
2022-06-11 23:32:46 -03:00
|
|
|
if (inactive) {
|
|
|
|
// while inactive we reset the filter so when it activates the first output
|
|
|
|
// will be the first input sample
|
|
|
|
notch.filter[instance].reset();
|
|
|
|
} else {
|
|
|
|
gyro_filtered = notch.filter[instance].apply(gyro_filtered);
|
|
|
|
}
|
2022-09-22 11:35:48 -03:00
|
|
|
save_gyro_window(instance, gyro_filtered, filter_phase++);
|
2022-02-17 01:43:09 -04:00
|
|
|
}
|
2024-02-12 20:26:07 -04:00
|
|
|
#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
2022-02-17 01:43:09 -04:00
|
|
|
|
2022-09-22 11:35:48 -03:00
|
|
|
// apply the low pass filter last to attenuate any notch induced noise
|
2022-02-17 01:43:09 -04:00
|
|
|
gyro_filtered = _imu._gyro_filter[instance].apply(gyro_filtered);
|
|
|
|
|
|
|
|
// if the filtering failed in any way then reset the filters and keep the old value
|
|
|
|
if (gyro_filtered.is_nan() || gyro_filtered.is_inf()) {
|
|
|
|
_imu._gyro_filter[instance].reset();
|
2022-11-28 05:33:50 -04:00
|
|
|
#if HAL_GYROFFT_ENABLED
|
2022-09-22 11:35:48 -03:00
|
|
|
_imu._post_filter_gyro_filter[instance].reset();
|
|
|
|
#endif
|
2024-02-12 20:26:07 -04:00
|
|
|
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
2022-02-17 01:43:09 -04:00
|
|
|
for (auto ¬ch : _imu.harmonic_notches) {
|
|
|
|
notch.filter[instance].reset();
|
|
|
|
}
|
2024-02-12 20:26:07 -04:00
|
|
|
#endif
|
2022-02-17 01:43:09 -04:00
|
|
|
} else {
|
|
|
|
_imu._gyro_filtered[instance] = gyro_filtered;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-09-08 14:05:37 -03:00
|
|
|
void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance,
|
2015-11-15 20:58:08 -04:00
|
|
|
const Vector3f &gyro,
|
|
|
|
uint64_t sample_us)
|
2015-09-08 14:05:37 -03:00
|
|
|
{
|
2024-07-09 08:30:23 -03:00
|
|
|
if (has_been_killed(instance)) {
|
2019-04-18 01:24:01 -03:00
|
|
|
return;
|
|
|
|
}
|
2015-09-10 09:34:01 -03:00
|
|
|
float dt;
|
|
|
|
|
2017-05-01 00:01:43 -03:00
|
|
|
_update_sensor_rate(_imu._sample_gyro_count[instance], _imu._sample_gyro_start_us[instance],
|
|
|
|
_imu._gyro_raw_sample_rates[instance]);
|
|
|
|
|
2019-07-04 22:51:30 -03:00
|
|
|
uint64_t last_sample_us = _imu._gyro_last_sample_us[instance];
|
|
|
|
|
2017-04-30 21:53:41 -03:00
|
|
|
/*
|
|
|
|
we have two classes of sensors. FIFO based sensors produce data
|
|
|
|
at a very predictable overall rate, but the data comes in
|
|
|
|
bunches, so we use the provided sample rate for deltaT. Non-FIFO
|
|
|
|
sensors don't bunch up samples, but also tend to vary in actual
|
|
|
|
rate, so we use the provided sample_us to get the deltaT. The
|
|
|
|
difference between the two is whether sample_us is provided.
|
|
|
|
*/
|
|
|
|
if (sample_us != 0 && _imu._gyro_last_sample_us[instance] != 0) {
|
2019-04-04 19:07:44 -03:00
|
|
|
dt = (sample_us - _imu._gyro_last_sample_us[instance]) * 1.0e-6f;
|
2019-07-04 22:51:30 -03:00
|
|
|
_imu._gyro_last_sample_us[instance] = sample_us;
|
2017-04-30 21:53:41 -03:00
|
|
|
} else {
|
2020-12-28 22:29:40 -04:00
|
|
|
// don't accept below 40Hz
|
|
|
|
if (_imu._gyro_raw_sample_rates[instance] < 40) {
|
2017-04-30 21:53:41 -03:00
|
|
|
return;
|
|
|
|
}
|
2015-09-10 09:34:01 -03:00
|
|
|
|
2017-04-30 21:53:41 -03:00
|
|
|
dt = 1.0f / _imu._gyro_raw_sample_rates[instance];
|
2019-07-04 22:51:30 -03:00
|
|
|
_imu._gyro_last_sample_us[instance] = AP_HAL::micros64();
|
2019-09-27 16:56:45 -03:00
|
|
|
sample_us = _imu._gyro_last_sample_us[instance];
|
2017-04-30 21:53:41 -03:00
|
|
|
}
|
2015-09-10 09:34:01 -03:00
|
|
|
|
2018-02-09 04:10:30 -04:00
|
|
|
#if AP_MODULE_SUPPORTED
|
2016-07-12 08:50:46 -03:00
|
|
|
// call gyro_sample hook if any
|
|
|
|
AP_Module::call_hook_gyro_sample(instance, dt, gyro);
|
2018-02-09 04:10:30 -04:00
|
|
|
#endif
|
2017-01-17 12:49:27 -04:00
|
|
|
|
|
|
|
// push gyros if optical flow present
|
2019-07-04 22:51:30 -03:00
|
|
|
if (hal.opticalflow) {
|
2017-01-17 12:49:27 -04:00
|
|
|
hal.opticalflow->push_gyro(gyro.x, gyro.y, dt);
|
2019-07-04 22:51:30 -03:00
|
|
|
}
|
2016-07-12 08:50:46 -03:00
|
|
|
|
2015-09-10 09:34:01 -03:00
|
|
|
// compute delta angle
|
|
|
|
Vector3f delta_angle = (gyro + _imu._last_raw_gyro[instance]) * 0.5f * dt;
|
|
|
|
|
|
|
|
// compute coning correction
|
|
|
|
// see page 26 of:
|
|
|
|
// Tian et al (2010) Three-loop Integration of GPS and Strapdown INS with Coning and Sculling Compensation
|
|
|
|
// Available: http://www.sage.unsw.edu.au/snap/publications/tian_etal2010b.pdf
|
|
|
|
// see also examples/coning.py
|
|
|
|
Vector3f delta_coning = (_imu._delta_angle_acc[instance] +
|
|
|
|
_imu._last_delta_angle[instance] * (1.0f / 6.0f));
|
|
|
|
delta_coning = delta_coning % delta_angle;
|
|
|
|
delta_coning *= 0.5f;
|
|
|
|
|
2018-10-11 20:35:03 -03:00
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_sem);
|
2019-07-04 22:51:30 -03:00
|
|
|
uint64_t now = AP_HAL::micros64();
|
|
|
|
|
|
|
|
if (now - last_sample_us > 100000U) {
|
|
|
|
// zero accumulator if sensor was unhealthy for 0.1s
|
|
|
|
_imu._delta_angle_acc[instance].zero();
|
|
|
|
_imu._delta_angle_acc_dt[instance] = 0;
|
|
|
|
dt = 0;
|
|
|
|
delta_angle.zero();
|
|
|
|
}
|
|
|
|
|
2016-11-17 15:31:05 -04:00
|
|
|
// integrate delta angle accumulator
|
|
|
|
// the angles and coning corrections are accumulated separately in the
|
|
|
|
// referenced paper, but in simulation little difference was found between
|
|
|
|
// integrating together and integrating separately (see examples/coning.py)
|
|
|
|
_imu._delta_angle_acc[instance] += delta_angle + delta_coning;
|
|
|
|
_imu._delta_angle_acc_dt[instance] += dt;
|
2015-09-10 09:34:01 -03:00
|
|
|
|
2016-11-17 15:31:05 -04:00
|
|
|
// save previous delta angle for coning correction
|
|
|
|
_imu._last_delta_angle[instance] = delta_angle;
|
|
|
|
_imu._last_raw_gyro[instance] = gyro;
|
2020-05-29 13:28:06 -03:00
|
|
|
|
2022-09-22 11:35:48 -03:00
|
|
|
// apply gyro filters and sample for FFT
|
2022-02-17 01:43:09 -04:00
|
|
|
apply_gyro_filters(instance, gyro);
|
2019-08-30 04:33:42 -03:00
|
|
|
|
2016-11-03 21:06:19 -03:00
|
|
|
_imu._new_gyro_data[instance] = true;
|
2015-11-21 02:55:51 -04:00
|
|
|
}
|
2015-11-15 20:05:20 -04:00
|
|
|
|
2022-08-03 06:27:34 -03:00
|
|
|
// 5us
|
2023-09-29 18:26:31 -03:00
|
|
|
log_gyro_raw(instance, sample_us, gyro, _imu._gyro_filtered[instance]);
|
2017-09-08 11:42:57 -03:00
|
|
|
}
|
|
|
|
|
2021-12-13 22:44:21 -04:00
|
|
|
/*
|
|
|
|
handle a delta-angle sample from the backend. This assumes FIFO
|
|
|
|
style sampling and the sample should not be rotated or corrected for
|
|
|
|
offsets.
|
|
|
|
This function should be used when the sensor driver can directly
|
|
|
|
provide delta-angle values from the sensor.
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::_notify_new_delta_angle(uint8_t instance, const Vector3f &dangle)
|
|
|
|
{
|
2024-07-09 08:30:23 -03:00
|
|
|
if (has_been_killed(instance)) {
|
2021-12-13 22:44:21 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
float dt;
|
|
|
|
|
|
|
|
_update_sensor_rate(_imu._sample_gyro_count[instance], _imu._sample_gyro_start_us[instance],
|
|
|
|
_imu._gyro_raw_sample_rates[instance]);
|
|
|
|
|
|
|
|
uint64_t last_sample_us = _imu._gyro_last_sample_us[instance];
|
|
|
|
|
|
|
|
// don't accept below 40Hz
|
|
|
|
if (_imu._gyro_raw_sample_rates[instance] < 40) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
dt = 1.0f / _imu._gyro_raw_sample_rates[instance];
|
|
|
|
_imu._gyro_last_sample_us[instance] = AP_HAL::micros64();
|
|
|
|
uint64_t sample_us = _imu._gyro_last_sample_us[instance];
|
|
|
|
|
|
|
|
Vector3f gyro = dangle / dt;
|
|
|
|
|
|
|
|
_rotate_and_correct_gyro(instance, gyro);
|
|
|
|
|
|
|
|
#if AP_MODULE_SUPPORTED
|
|
|
|
// call gyro_sample hook if any
|
|
|
|
AP_Module::call_hook_gyro_sample(instance, dt, gyro);
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// push gyros if optical flow present
|
|
|
|
if (hal.opticalflow) {
|
|
|
|
hal.opticalflow->push_gyro(gyro.x, gyro.y, dt);
|
|
|
|
}
|
|
|
|
|
|
|
|
// compute delta angle, including corrections
|
|
|
|
Vector3f delta_angle = gyro * dt;
|
|
|
|
|
|
|
|
// compute coning correction
|
|
|
|
// see page 26 of:
|
|
|
|
// Tian et al (2010) Three-loop Integration of GPS and Strapdown INS with Coning and Sculling Compensation
|
|
|
|
// Available: http://www.sage.unsw.edu.au/snap/publications/tian_etal2010b.pdf
|
|
|
|
// see also examples/coning.py
|
|
|
|
Vector3f delta_coning = (_imu._delta_angle_acc[instance] +
|
|
|
|
_imu._last_delta_angle[instance] * (1.0f / 6.0f));
|
|
|
|
delta_coning = delta_coning % delta_angle;
|
|
|
|
delta_coning *= 0.5f;
|
|
|
|
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_sem);
|
|
|
|
uint64_t now = AP_HAL::micros64();
|
|
|
|
|
|
|
|
if (now - last_sample_us > 100000U) {
|
|
|
|
// zero accumulator if sensor was unhealthy for 0.1s
|
|
|
|
_imu._delta_angle_acc[instance].zero();
|
|
|
|
_imu._delta_angle_acc_dt[instance] = 0;
|
|
|
|
dt = 0;
|
|
|
|
delta_angle.zero();
|
|
|
|
}
|
|
|
|
|
|
|
|
// integrate delta angle accumulator
|
|
|
|
// the angles and coning corrections are accumulated separately in the
|
|
|
|
// referenced paper, but in simulation little difference was found between
|
|
|
|
// integrating together and integrating separately (see examples/coning.py)
|
|
|
|
_imu._delta_angle_acc[instance] += delta_angle + delta_coning;
|
|
|
|
_imu._delta_angle_acc_dt[instance] += dt;
|
|
|
|
|
|
|
|
// save previous delta angle for coning correction
|
|
|
|
_imu._last_delta_angle[instance] = delta_angle;
|
|
|
|
_imu._last_raw_gyro[instance] = gyro;
|
|
|
|
|
2022-09-22 11:35:48 -03:00
|
|
|
// apply gyro filters and sample for FFT
|
2022-02-17 01:43:09 -04:00
|
|
|
apply_gyro_filters(instance, gyro);
|
2021-12-13 22:44:21 -04:00
|
|
|
|
|
|
|
_imu._new_gyro_data[instance] = true;
|
|
|
|
}
|
|
|
|
|
2023-09-29 18:26:31 -03:00
|
|
|
log_gyro_raw(instance, sample_us, gyro, _imu._gyro_filtered[instance]);
|
2021-12-13 22:44:21 -04:00
|
|
|
}
|
|
|
|
|
2023-09-29 18:26:31 -03:00
|
|
|
void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &raw_gyro, const Vector3f &filtered_gyro)
|
2017-09-08 11:42:57 -03:00
|
|
|
{
|
2022-06-05 08:28:40 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2019-02-11 04:32:47 -04:00
|
|
|
AP_Logger *logger = AP_Logger::get_singleton();
|
|
|
|
if (logger == nullptr) {
|
2017-09-08 11:42:57 -03:00
|
|
|
// should not have been called
|
|
|
|
return;
|
|
|
|
}
|
2023-09-29 18:26:31 -03:00
|
|
|
|
2024-01-10 18:16:57 -04:00
|
|
|
#if AP_AHRS_ENABLED
|
|
|
|
const bool log_because_primary_gyro = _imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::PRIMARY_GYRO_ONLY) && (instance == AP::ahrs().get_primary_gyro_index());
|
|
|
|
#else
|
|
|
|
const bool log_because_primary_gyro = false;
|
|
|
|
#endif
|
|
|
|
|
2023-09-29 18:26:31 -03:00
|
|
|
if (_imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::ALL_GYROS) ||
|
2024-01-10 18:16:57 -04:00
|
|
|
log_because_primary_gyro ||
|
2023-09-29 18:26:31 -03:00
|
|
|
should_log_imu_raw()) {
|
|
|
|
|
|
|
|
if (_imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::PRE_AND_POST_FILTER)) {
|
|
|
|
// Both pre and post, offset post instance as batch sampler does
|
|
|
|
Write_GYR(instance, sample_us, raw_gyro);
|
|
|
|
Write_GYR(instance + _imu._gyro_count, sample_us, filtered_gyro);
|
|
|
|
|
|
|
|
} else if (_imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::POST_FILTER)) {
|
|
|
|
// Just post
|
|
|
|
Write_GYR(instance, sample_us, filtered_gyro);
|
|
|
|
|
|
|
|
} else {
|
|
|
|
// Just pre
|
|
|
|
Write_GYR(instance, sample_us, raw_gyro);
|
|
|
|
|
|
|
|
}
|
2017-10-03 20:44:07 -03:00
|
|
|
} else {
|
2023-01-03 01:51:51 -04:00
|
|
|
#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED
|
2018-03-18 20:28:33 -03:00
|
|
|
if (!_imu.batchsampler.doing_sensor_rate_logging()) {
|
2023-09-29 18:26:31 -03:00
|
|
|
_imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, sample_us,
|
|
|
|
!_imu.batchsampler.doing_post_filter_logging() ? raw_gyro : filtered_gyro);
|
2018-03-18 20:28:33 -03:00
|
|
|
}
|
2023-01-03 01:51:51 -04:00
|
|
|
#endif
|
2015-11-15 20:58:08 -04:00
|
|
|
}
|
2022-06-05 08:28:40 -03:00
|
|
|
#endif
|
2015-09-08 14:05:37 -03:00
|
|
|
}
|
|
|
|
|
2014-10-14 01:48:33 -03:00
|
|
|
/*
|
|
|
|
rotate accel vector, scale and add the accel offset
|
|
|
|
*/
|
2021-09-14 17:28:20 -03:00
|
|
|
void AP_InertialSensor_Backend::_publish_accel(uint8_t instance, const Vector3f &accel) /* front end */
|
2014-10-14 01:48:33 -03:00
|
|
|
{
|
2024-07-09 08:30:23 -03:00
|
|
|
if (has_been_killed(instance)) {
|
2019-04-18 01:24:01 -03:00
|
|
|
return;
|
|
|
|
}
|
2014-10-15 05:54:30 -03:00
|
|
|
_imu._accel[instance] = accel;
|
2014-10-15 23:27:22 -03:00
|
|
|
_imu._accel_healthy[instance] = true;
|
2015-09-08 11:42:28 -03:00
|
|
|
|
|
|
|
// publish delta velocity
|
|
|
|
_imu._delta_velocity[instance] = _imu._delta_velocity_acc[instance];
|
|
|
|
_imu._delta_velocity_dt[instance] = _imu._delta_velocity_acc_dt[instance];
|
|
|
|
_imu._delta_velocity_valid[instance] = true;
|
2015-07-20 17:25:40 -03:00
|
|
|
|
2021-08-30 03:47:54 -03:00
|
|
|
_imu._delta_velocity_acc[instance].zero();
|
|
|
|
_imu._delta_velocity_acc_dt[instance] = 0;
|
2015-07-20 17:25:40 -03:00
|
|
|
|
2016-10-30 02:24:21 -03:00
|
|
|
if (_imu._accel_calibrator != nullptr && _imu._accel_calibrator[instance].get_status() == ACCEL_CAL_COLLECTING_SAMPLE) {
|
2015-07-20 17:25:40 -03:00
|
|
|
Vector3f cal_sample = _imu._delta_velocity[instance];
|
|
|
|
|
2021-01-07 20:46:35 -04:00
|
|
|
// remove rotation. Note that we don't need to remove offsets or scale factor as those
|
|
|
|
// are not applied when calibrating
|
2015-07-20 17:25:40 -03:00
|
|
|
cal_sample.rotate_inverse(_imu._board_orientation);
|
|
|
|
|
|
|
|
_imu._accel_calibrator[instance].new_sample(cal_sample, _imu._delta_velocity_dt[instance]);
|
|
|
|
}
|
2014-10-14 01:48:33 -03:00
|
|
|
}
|
2014-10-16 17:52:21 -03:00
|
|
|
|
2015-08-27 16:05:13 -03:00
|
|
|
void AP_InertialSensor_Backend::_notify_new_accel_raw_sample(uint8_t instance,
|
2015-11-15 20:58:08 -04:00
|
|
|
const Vector3f &accel,
|
2016-08-31 01:56:27 -03:00
|
|
|
uint64_t sample_us,
|
|
|
|
bool fsync_set)
|
2015-08-27 16:05:13 -03:00
|
|
|
{
|
2024-07-09 08:30:23 -03:00
|
|
|
if (has_been_killed(instance)) {
|
2019-04-18 01:24:01 -03:00
|
|
|
return;
|
|
|
|
}
|
2015-09-08 11:42:28 -03:00
|
|
|
float dt;
|
|
|
|
|
2017-05-01 00:01:43 -03:00
|
|
|
_update_sensor_rate(_imu._sample_accel_count[instance], _imu._sample_accel_start_us[instance],
|
|
|
|
_imu._accel_raw_sample_rates[instance]);
|
|
|
|
|
2019-07-04 22:51:30 -03:00
|
|
|
uint64_t last_sample_us = _imu._accel_last_sample_us[instance];
|
|
|
|
|
2017-04-30 21:53:41 -03:00
|
|
|
/*
|
|
|
|
we have two classes of sensors. FIFO based sensors produce data
|
|
|
|
at a very predictable overall rate, but the data comes in
|
|
|
|
bunches, so we use the provided sample rate for deltaT. Non-FIFO
|
|
|
|
sensors don't bunch up samples, but also tend to vary in actual
|
|
|
|
rate, so we use the provided sample_us to get the deltaT. The
|
|
|
|
difference between the two is whether sample_us is provided.
|
|
|
|
*/
|
|
|
|
if (sample_us != 0 && _imu._accel_last_sample_us[instance] != 0) {
|
2019-04-04 19:07:44 -03:00
|
|
|
dt = (sample_us - _imu._accel_last_sample_us[instance]) * 1.0e-6f;
|
2019-07-04 22:51:30 -03:00
|
|
|
_imu._accel_last_sample_us[instance] = sample_us;
|
2017-04-30 21:53:41 -03:00
|
|
|
} else {
|
2020-12-28 22:29:40 -04:00
|
|
|
// don't accept below 40Hz
|
|
|
|
if (_imu._accel_raw_sample_rates[instance] < 40) {
|
2017-04-30 21:53:41 -03:00
|
|
|
return;
|
|
|
|
}
|
2015-09-08 11:42:28 -03:00
|
|
|
|
2017-04-30 21:53:41 -03:00
|
|
|
dt = 1.0f / _imu._accel_raw_sample_rates[instance];
|
2019-07-04 22:51:30 -03:00
|
|
|
_imu._accel_last_sample_us[instance] = AP_HAL::micros64();
|
2019-09-27 16:56:45 -03:00
|
|
|
sample_us = _imu._accel_last_sample_us[instance];
|
2017-04-30 21:53:41 -03:00
|
|
|
}
|
2015-09-08 11:42:28 -03:00
|
|
|
|
2018-02-09 04:10:30 -04:00
|
|
|
#if AP_MODULE_SUPPORTED
|
2017-04-30 21:53:41 -03:00
|
|
|
// call accel_sample hook if any
|
2016-08-31 01:56:27 -03:00
|
|
|
AP_Module::call_hook_accel_sample(instance, dt, accel, fsync_set);
|
2018-02-09 04:10:30 -04:00
|
|
|
#endif
|
2016-07-12 08:50:46 -03:00
|
|
|
|
2015-09-08 11:42:28 -03:00
|
|
|
_imu.calc_vibration_and_clipping(instance, accel, dt);
|
|
|
|
|
2018-10-11 20:35:03 -03:00
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_sem);
|
|
|
|
|
2019-07-04 22:51:30 -03:00
|
|
|
uint64_t now = AP_HAL::micros64();
|
|
|
|
|
|
|
|
if (now - last_sample_us > 100000U) {
|
|
|
|
// zero accumulator if sensor was unhealthy for 0.1s
|
|
|
|
_imu._delta_velocity_acc[instance].zero();
|
|
|
|
_imu._delta_velocity_acc_dt[instance] = 0;
|
|
|
|
dt = 0;
|
|
|
|
}
|
|
|
|
|
2016-11-17 15:31:05 -04:00
|
|
|
// delta velocity
|
|
|
|
_imu._delta_velocity_acc[instance] += accel * dt;
|
|
|
|
_imu._delta_velocity_acc_dt[instance] += dt;
|
|
|
|
|
2016-11-03 21:06:19 -03:00
|
|
|
_imu._accel_filtered[instance] = _imu._accel_filter[instance].apply(accel);
|
|
|
|
if (_imu._accel_filtered[instance].is_nan() || _imu._accel_filtered[instance].is_inf()) {
|
|
|
|
_imu._accel_filter[instance].reset();
|
|
|
|
}
|
2015-11-15 20:05:20 -04:00
|
|
|
|
2016-11-03 21:06:19 -03:00
|
|
|
_imu.set_accel_peak_hold(instance, _imu._accel_filtered[instance]);
|
2015-12-29 13:18:07 -04:00
|
|
|
|
2016-11-03 21:06:19 -03:00
|
|
|
_imu._new_accel_data[instance] = true;
|
|
|
|
}
|
2015-11-15 20:58:08 -04:00
|
|
|
|
2022-08-03 06:27:34 -03:00
|
|
|
// 5us
|
2023-01-03 01:51:51 -04:00
|
|
|
#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED
|
2019-05-17 12:57:43 -03:00
|
|
|
if (!_imu.batchsampler.doing_post_filter_logging()) {
|
|
|
|
log_accel_raw(instance, sample_us, accel);
|
|
|
|
} else {
|
|
|
|
log_accel_raw(instance, sample_us, _imu._accel_filtered[instance]);
|
|
|
|
}
|
2023-01-03 01:51:51 -04:00
|
|
|
#else
|
|
|
|
// assume we're doing pre-filter logging:
|
|
|
|
log_accel_raw(instance, sample_us, accel);
|
|
|
|
#endif
|
2017-09-08 11:42:57 -03:00
|
|
|
}
|
|
|
|
|
2021-12-13 22:44:21 -04:00
|
|
|
/*
|
|
|
|
handle a delta-velocity sample from the backend. This assumes FIFO style sampling and
|
|
|
|
the sample should not be rotated or corrected for offsets
|
|
|
|
|
|
|
|
This function should be used when the sensor driver can directly
|
|
|
|
provide delta-velocity values from the sensor.
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::_notify_new_delta_velocity(uint8_t instance, const Vector3f &dvel)
|
|
|
|
{
|
2024-07-09 08:30:23 -03:00
|
|
|
if (has_been_killed(instance)) {
|
2021-12-13 22:44:21 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
float dt;
|
|
|
|
|
|
|
|
_update_sensor_rate(_imu._sample_accel_count[instance], _imu._sample_accel_start_us[instance],
|
|
|
|
_imu._accel_raw_sample_rates[instance]);
|
|
|
|
|
|
|
|
uint64_t last_sample_us = _imu._accel_last_sample_us[instance];
|
|
|
|
|
|
|
|
// don't accept below 40Hz
|
|
|
|
if (_imu._accel_raw_sample_rates[instance] < 40) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
dt = 1.0f / _imu._accel_raw_sample_rates[instance];
|
|
|
|
_imu._accel_last_sample_us[instance] = AP_HAL::micros64();
|
|
|
|
uint64_t sample_us = _imu._accel_last_sample_us[instance];
|
|
|
|
|
|
|
|
Vector3f accel = dvel / dt;
|
|
|
|
|
|
|
|
_rotate_and_correct_accel(instance, accel);
|
|
|
|
|
|
|
|
#if AP_MODULE_SUPPORTED
|
|
|
|
// call accel_sample hook if any
|
|
|
|
AP_Module::call_hook_accel_sample(instance, dt, accel, false);
|
|
|
|
#endif
|
|
|
|
|
|
|
|
_imu.calc_vibration_and_clipping(instance, accel, dt);
|
|
|
|
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_sem);
|
|
|
|
|
|
|
|
uint64_t now = AP_HAL::micros64();
|
|
|
|
|
|
|
|
if (now - last_sample_us > 100000U) {
|
|
|
|
// zero accumulator if sensor was unhealthy for 0.1s
|
|
|
|
_imu._delta_velocity_acc[instance].zero();
|
|
|
|
_imu._delta_velocity_acc_dt[instance] = 0;
|
|
|
|
dt = 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
// delta velocity including corrections
|
|
|
|
_imu._delta_velocity_acc[instance] += accel * dt;
|
|
|
|
_imu._delta_velocity_acc_dt[instance] += dt;
|
|
|
|
|
|
|
|
_imu._accel_filtered[instance] = _imu._accel_filter[instance].apply(accel);
|
|
|
|
if (_imu._accel_filtered[instance].is_nan() || _imu._accel_filtered[instance].is_inf()) {
|
|
|
|
_imu._accel_filter[instance].reset();
|
|
|
|
}
|
|
|
|
|
|
|
|
_imu.set_accel_peak_hold(instance, _imu._accel_filtered[instance]);
|
|
|
|
|
|
|
|
_imu._new_accel_data[instance] = true;
|
|
|
|
}
|
|
|
|
|
2023-01-03 01:51:51 -04:00
|
|
|
#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED
|
2021-12-13 22:44:21 -04:00
|
|
|
if (!_imu.batchsampler.doing_post_filter_logging()) {
|
|
|
|
log_accel_raw(instance, sample_us, accel);
|
|
|
|
} else {
|
|
|
|
log_accel_raw(instance, sample_us, _imu._accel_filtered[instance]);
|
|
|
|
}
|
2023-01-03 01:51:51 -04:00
|
|
|
#else
|
|
|
|
// assume we're doing pre-filter logging
|
|
|
|
log_accel_raw(instance, sample_us, accel);
|
|
|
|
#endif
|
2021-12-13 22:44:21 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2023-08-27 23:02:12 -03:00
|
|
|
void AP_InertialSensor_Backend::_notify_new_accel_sensor_rate_sample(uint8_t instance, const Vector3f &_accel)
|
2018-03-07 04:09:15 -04:00
|
|
|
{
|
2023-01-03 01:51:51 -04:00
|
|
|
#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED
|
2018-03-18 20:28:33 -03:00
|
|
|
if (!_imu.batchsampler.doing_sensor_rate_logging()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2023-08-27 23:02:12 -03:00
|
|
|
// get batch sampling in correct orientation
|
|
|
|
Vector3f accel = _accel;
|
|
|
|
accel.rotate(_imu._accel_orientation[instance]);
|
|
|
|
|
2018-03-07 04:09:15 -04:00
|
|
|
_imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_ACCEL, AP_HAL::micros64(), accel);
|
2023-01-03 01:51:51 -04:00
|
|
|
#endif
|
2018-03-07 04:09:15 -04:00
|
|
|
}
|
|
|
|
|
2023-08-27 23:02:12 -03:00
|
|
|
void AP_InertialSensor_Backend::_notify_new_gyro_sensor_rate_sample(uint8_t instance, const Vector3f &_gyro)
|
2018-03-07 04:09:15 -04:00
|
|
|
{
|
2023-01-03 01:51:51 -04:00
|
|
|
#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED
|
2018-03-18 20:28:33 -03:00
|
|
|
if (!_imu.batchsampler.doing_sensor_rate_logging()) {
|
|
|
|
return;
|
|
|
|
}
|
2023-08-27 23:02:12 -03:00
|
|
|
|
|
|
|
// get batch sampling in correct orientation
|
|
|
|
Vector3f gyro = _gyro;
|
|
|
|
gyro.rotate(_imu._gyro_orientation[instance]);
|
|
|
|
|
2018-03-07 04:09:15 -04:00
|
|
|
_imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, AP_HAL::micros64(), gyro);
|
2023-01-03 01:51:51 -04:00
|
|
|
#endif
|
2018-03-07 04:09:15 -04:00
|
|
|
}
|
|
|
|
|
2017-09-08 11:42:57 -03:00
|
|
|
void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &accel)
|
|
|
|
{
|
2022-06-05 08:28:40 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2019-02-11 04:32:47 -04:00
|
|
|
AP_Logger *logger = AP_Logger::get_singleton();
|
|
|
|
if (logger == nullptr) {
|
2017-09-08 11:42:57 -03:00
|
|
|
// should not have been called
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (should_log_imu_raw()) {
|
2021-04-30 00:28:37 -03:00
|
|
|
Write_ACC(instance, sample_us, accel);
|
2017-10-03 20:44:07 -03:00
|
|
|
} else {
|
2023-01-03 01:51:51 -04:00
|
|
|
#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED
|
2018-03-18 20:28:33 -03:00
|
|
|
if (!_imu.batchsampler.doing_sensor_rate_logging()) {
|
|
|
|
_imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_ACCEL, sample_us, accel);
|
|
|
|
}
|
2023-01-03 01:51:51 -04:00
|
|
|
#endif
|
2015-11-15 20:58:08 -04:00
|
|
|
}
|
2022-06-05 08:28:40 -03:00
|
|
|
#endif
|
2015-08-27 16:05:13 -03:00
|
|
|
}
|
|
|
|
|
2015-06-09 17:47:16 -03:00
|
|
|
void AP_InertialSensor_Backend::_set_accel_max_abs_offset(uint8_t instance,
|
2015-06-29 21:51:43 -03:00
|
|
|
float max_offset)
|
2015-06-09 17:47:16 -03:00
|
|
|
{
|
2015-06-29 21:51:43 -03:00
|
|
|
_imu._accel_max_abs_offsets[instance] = max_offset;
|
2015-06-09 17:47:16 -03:00
|
|
|
}
|
|
|
|
|
2016-11-10 02:14:38 -04:00
|
|
|
// increment accelerometer error_count
|
|
|
|
void AP_InertialSensor_Backend::_inc_accel_error_count(uint8_t instance)
|
|
|
|
{
|
|
|
|
_imu._accel_error_count[instance]++;
|
|
|
|
}
|
|
|
|
|
|
|
|
// increment gyro error_count
|
|
|
|
void AP_InertialSensor_Backend::_inc_gyro_error_count(uint8_t instance)
|
|
|
|
{
|
|
|
|
_imu._gyro_error_count[instance]++;
|
|
|
|
}
|
|
|
|
|
2015-03-16 23:32:54 -03:00
|
|
|
/*
|
|
|
|
publish a temperature value for an instance
|
|
|
|
*/
|
2021-09-14 17:28:20 -03:00
|
|
|
void AP_InertialSensor_Backend::_publish_temperature(uint8_t instance, float temperature) /* front end */
|
2015-03-16 23:32:54 -03:00
|
|
|
{
|
2024-07-09 08:30:23 -03:00
|
|
|
if (has_been_killed(instance)) {
|
2019-04-18 01:24:01 -03:00
|
|
|
return;
|
|
|
|
}
|
2015-03-16 23:32:54 -03:00
|
|
|
_imu._temperature[instance] = temperature;
|
2016-06-15 05:02:12 -03:00
|
|
|
|
2019-11-01 23:32:59 -03:00
|
|
|
#if HAL_HAVE_IMU_HEATER
|
2016-06-15 05:02:12 -03:00
|
|
|
/* give the temperature to the control loop in order to keep it constant*/
|
2023-03-03 16:42:21 -04:00
|
|
|
if (instance == AP_HEATER_IMU_INSTANCE) {
|
2019-11-01 23:32:59 -03:00
|
|
|
AP_BoardConfig *bc = AP::boardConfig();
|
|
|
|
if (bc) {
|
|
|
|
bc->set_imu_temp(temperature);
|
|
|
|
}
|
2016-06-15 05:02:12 -03:00
|
|
|
}
|
2019-11-01 23:32:59 -03:00
|
|
|
#endif
|
2015-03-16 23:32:54 -03:00
|
|
|
}
|
2015-11-15 20:05:20 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
common gyro update function for all backends
|
|
|
|
*/
|
2021-09-14 17:28:20 -03:00
|
|
|
void AP_InertialSensor_Backend::update_gyro(uint8_t instance) /* front end */
|
2015-11-15 20:05:20 -04:00
|
|
|
{
|
2018-10-11 20:35:03 -03:00
|
|
|
WITH_SEMAPHORE(_sem);
|
2015-11-15 20:05:20 -04:00
|
|
|
|
2024-07-09 08:30:23 -03:00
|
|
|
if (has_been_killed(instance)) {
|
2019-04-18 01:24:01 -03:00
|
|
|
return;
|
|
|
|
}
|
2015-11-15 20:05:20 -04:00
|
|
|
if (_imu._new_gyro_data[instance]) {
|
|
|
|
_publish_gyro(instance, _imu._gyro_filtered[instance]);
|
2022-11-28 05:33:50 -04:00
|
|
|
#if HAL_GYROFFT_ENABLED
|
2022-09-22 11:35:48 -03:00
|
|
|
// copy the gyro samples from the backend to the frontend window for FFTs sampling at less than IMU rate
|
|
|
|
_imu._gyro_for_fft[instance] = _imu._last_gyro_for_fft[instance];
|
2020-01-03 15:52:33 -04:00
|
|
|
#endif
|
2015-11-15 20:05:20 -04:00
|
|
|
_imu._new_gyro_data[instance] = false;
|
|
|
|
}
|
|
|
|
|
2024-06-03 14:38:08 -03:00
|
|
|
update_gyro_filters(instance);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
propagate filter changes from front end to backend
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::update_gyro_filters(uint8_t instance) /* front end */
|
|
|
|
{
|
2015-11-15 20:05:20 -04:00
|
|
|
// possibly update filter frequency
|
2022-04-17 04:35:57 -03:00
|
|
|
const float gyro_rate = _gyro_raw_sample_rate(instance);
|
|
|
|
|
2019-08-30 04:33:42 -03:00
|
|
|
if (_last_gyro_filter_hz != _gyro_filter_cutoff() || sensors_converging()) {
|
2022-04-17 04:35:57 -03:00
|
|
|
_imu._gyro_filter[instance].set_cutoff_frequency(gyro_rate, _gyro_filter_cutoff());
|
2022-11-28 05:33:50 -04:00
|
|
|
#if HAL_GYROFFT_ENABLED
|
2022-09-22 11:35:48 -03:00
|
|
|
_imu._post_filter_gyro_filter[instance].set_cutoff_frequency(gyro_rate, _gyro_filter_cutoff());
|
|
|
|
#endif
|
2019-06-17 05:44:12 -03:00
|
|
|
_last_gyro_filter_hz = _gyro_filter_cutoff();
|
|
|
|
}
|
2022-04-17 04:35:57 -03:00
|
|
|
|
2024-02-12 20:26:07 -04:00
|
|
|
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
2022-04-17 04:35:57 -03:00
|
|
|
for (auto ¬ch : _imu.harmonic_notches) {
|
|
|
|
if (notch.params.enabled()) {
|
|
|
|
notch.update_params(instance, sensors_converging(), gyro_rate);
|
|
|
|
}
|
|
|
|
}
|
2024-02-12 20:26:07 -04:00
|
|
|
#endif
|
2015-11-15 20:05:20 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
common accel update function for all backends
|
|
|
|
*/
|
2021-09-14 17:28:20 -03:00
|
|
|
void AP_InertialSensor_Backend::update_accel(uint8_t instance) /* front end */
|
2015-11-15 20:05:20 -04:00
|
|
|
{
|
2018-10-11 20:35:03 -03:00
|
|
|
WITH_SEMAPHORE(_sem);
|
2015-11-15 20:05:20 -04:00
|
|
|
|
2024-07-09 08:30:23 -03:00
|
|
|
if (has_been_killed(instance)) {
|
2019-04-18 01:24:01 -03:00
|
|
|
return;
|
|
|
|
}
|
2015-11-15 20:05:20 -04:00
|
|
|
if (_imu._new_accel_data[instance]) {
|
|
|
|
_publish_accel(instance, _imu._accel_filtered[instance]);
|
|
|
|
_imu._new_accel_data[instance] = false;
|
|
|
|
}
|
2024-06-03 14:38:08 -03:00
|
|
|
|
|
|
|
update_accel_filters(instance);
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
propagate filter changes from front end to backend
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::update_accel_filters(uint8_t instance) /* front end */
|
|
|
|
{
|
2015-11-15 20:05:20 -04:00
|
|
|
// possibly update filter frequency
|
2019-06-17 05:44:12 -03:00
|
|
|
if (_last_accel_filter_hz != _accel_filter_cutoff()) {
|
2015-11-15 20:05:20 -04:00
|
|
|
_imu._accel_filter[instance].set_cutoff_frequency(_accel_raw_sample_rate(instance), _accel_filter_cutoff());
|
2019-06-17 05:44:12 -03:00
|
|
|
_last_accel_filter_hz = _accel_filter_cutoff();
|
2015-11-15 20:05:20 -04:00
|
|
|
}
|
|
|
|
}
|
2017-06-27 01:42:45 -03:00
|
|
|
|
2023-07-13 21:58:06 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2017-09-08 11:42:57 -03:00
|
|
|
bool AP_InertialSensor_Backend::should_log_imu_raw() const
|
2017-06-27 01:42:45 -03:00
|
|
|
{
|
|
|
|
if (_imu._log_raw_bit == (uint32_t)-1) {
|
|
|
|
// tracker does not set a bit
|
2017-09-08 11:42:57 -03:00
|
|
|
return false;
|
|
|
|
}
|
2019-02-11 04:32:47 -04:00
|
|
|
const AP_Logger *logger = AP_Logger::get_singleton();
|
|
|
|
if (logger == nullptr) {
|
2017-09-08 11:42:57 -03:00
|
|
|
return false;
|
2017-06-27 01:42:45 -03:00
|
|
|
}
|
2019-02-11 04:32:47 -04:00
|
|
|
if (!logger->should_log(_imu._log_raw_bit)) {
|
2017-09-08 11:42:57 -03:00
|
|
|
return false;
|
2017-06-27 01:42:45 -03:00
|
|
|
}
|
2017-09-08 11:42:57 -03:00
|
|
|
return true;
|
2017-06-27 01:42:45 -03:00
|
|
|
}
|
2023-07-13 21:58:06 -03:00
|
|
|
#endif // HAL_LOGGING_ENABLED
|
2018-02-09 04:10:30 -04:00
|
|
|
|
2021-02-23 19:32:39 -04:00
|
|
|
// log an unexpected change in a register for an IMU
|
|
|
|
void AP_InertialSensor_Backend::log_register_change(uint32_t bus_id, const AP_HAL::Device::checkreg ®)
|
|
|
|
{
|
2022-06-05 08:28:40 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2021-12-17 22:31:34 -04:00
|
|
|
AP::logger().Write("IREG", "TimeUS,DevID,Bank,Reg,Val", "QIBBB",
|
2021-02-23 19:32:39 -04:00
|
|
|
AP_HAL::micros64(),
|
|
|
|
bus_id,
|
|
|
|
reg.bank,
|
|
|
|
reg.regnum,
|
|
|
|
reg.value);
|
2022-06-05 08:28:40 -03:00
|
|
|
#endif
|
2021-02-23 19:32:39 -04:00
|
|
|
}
|