2014-10-14 01:48:33 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-10-14 01:48:33 -03:00
|
|
|
#include "AP_InertialSensor.h"
|
|
|
|
#include "AP_InertialSensor_Backend.h"
|
2015-11-15 20:58:08 -04:00
|
|
|
#include <DataFlash/DataFlash.h>
|
2014-10-14 01:48:33 -03:00
|
|
|
|
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) :
|
2014-10-15 23:14:56 -03:00
|
|
|
_imu(imu),
|
|
|
|
_product_id(AP_PRODUCT_ID_NONE)
|
2014-10-14 01:48:33 -03:00
|
|
|
{}
|
|
|
|
|
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
|
|
|
*/
|
|
|
|
|
2015-07-22 15:19:31 -03:00
|
|
|
// apply offsets
|
|
|
|
accel -= _imu._accel_offset[instance];
|
|
|
|
|
2015-03-10 04:05:41 -03:00
|
|
|
// apply scaling
|
2015-02-17 02:54:17 -04:00
|
|
|
const Vector3f &accel_scale = _imu._accel_scale[instance].get();
|
|
|
|
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
|
|
|
|
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)
|
|
|
|
{
|
|
|
|
// gyro calibration is always assumed to have been done in sensor frame
|
2015-02-17 02:54:17 -04:00
|
|
|
gyro -= _imu._gyro_offset[instance];
|
2015-03-10 04:05:41 -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
|
|
|
|
*/
|
2015-08-28 12:18:09 -03:00
|
|
|
void AP_InertialSensor_Backend::_publish_gyro(uint8_t instance, const Vector3f &gyro)
|
2014-10-14 01:48:33 -03:00
|
|
|
{
|
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
|
|
|
|
AP_InertialSensor: use raw sample rate terminology
In order to avoid confusion between sample rate from sensor and sample rate
from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to
the former.
The changes in the code were basically done with the following commands:
git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g"
git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g"
git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g"
git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g"
git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g"
git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g"
And also with minor changes on indentation and comments.
2015-09-10 09:56:28 -03:00
|
|
|
if (_imu._gyro_raw_sample_rates[instance] <= 0) {
|
2015-09-10 09:34:01 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// 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;
|
2015-02-17 02:54:17 -04:00
|
|
|
}
|
|
|
|
|
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
|
|
|
{
|
2015-09-10 09:34:01 -03:00
|
|
|
float dt;
|
|
|
|
|
AP_InertialSensor: use raw sample rate terminology
In order to avoid confusion between sample rate from sensor and sample rate
from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to
the former.
The changes in the code were basically done with the following commands:
git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g"
git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g"
git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g"
git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g"
git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g"
git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g"
And also with minor changes on indentation and comments.
2015-09-10 09:56:28 -03:00
|
|
|
if (_imu._gyro_raw_sample_rates[instance] <= 0) {
|
2015-09-10 09:34:01 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
AP_InertialSensor: use raw sample rate terminology
In order to avoid confusion between sample rate from sensor and sample rate
from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to
the former.
The changes in the code were basically done with the following commands:
git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g"
git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g"
git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g"
git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g"
git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g"
git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g"
And also with minor changes on indentation and comments.
2015-09-10 09:56:28 -03:00
|
|
|
dt = 1.0f / _imu._gyro_raw_sample_rates[instance];
|
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;
|
|
|
|
|
|
|
|
// 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;
|
2016-01-16 00:41:19 -04:00
|
|
|
_imu._delta_angle_acc_dt[instance] += dt;
|
2015-09-10 09:34:01 -03:00
|
|
|
|
|
|
|
// save previous delta angle for coning correction
|
|
|
|
_imu._last_delta_angle[instance] = delta_angle;
|
|
|
|
_imu._last_raw_gyro[instance] = gyro;
|
2015-11-15 20:05:20 -04:00
|
|
|
|
|
|
|
_imu._gyro_filtered[instance] = _imu._gyro_filter[instance].apply(gyro);
|
2015-11-21 02:55:51 -04:00
|
|
|
if (_imu._gyro_filtered[instance].is_nan() || _imu._gyro_filtered[instance].is_inf()) {
|
|
|
|
_imu._gyro_filter[instance].reset();
|
|
|
|
}
|
2015-11-15 20:05:20 -04:00
|
|
|
|
|
|
|
_imu._new_gyro_data[instance] = true;
|
2015-11-15 20:58:08 -04:00
|
|
|
|
|
|
|
DataFlash_Class *dataflash = get_dataflash();
|
|
|
|
if (dataflash != NULL) {
|
2015-11-19 23:11:52 -04:00
|
|
|
uint64_t now = AP_HAL::micros64();
|
2015-11-15 20:58:08 -04:00
|
|
|
struct log_GYRO pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GYR1_MSG+instance)),
|
|
|
|
time_us : now,
|
|
|
|
sample_us : sample_us?sample_us:now,
|
|
|
|
GyrX : gyro.x,
|
|
|
|
GyrY : gyro.y,
|
|
|
|
GyrZ : gyro.z
|
|
|
|
};
|
|
|
|
dataflash->WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
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
|
|
|
|
*/
|
2015-08-28 12:18:09 -03:00
|
|
|
void AP_InertialSensor_Backend::_publish_accel(uint8_t instance, const Vector3f &accel)
|
2014-10-14 01:48:33 -03:00
|
|
|
{
|
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
|
|
|
|
AP_InertialSensor: use raw sample rate terminology
In order to avoid confusion between sample rate from sensor and sample rate
from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to
the former.
The changes in the code were basically done with the following commands:
git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g"
git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g"
git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g"
git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g"
git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g"
git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g"
And also with minor changes on indentation and comments.
2015-09-10 09:56:28 -03:00
|
|
|
if (_imu._accel_raw_sample_rates[instance] <= 0) {
|
2015-09-08 11:42:28 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// 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
|
|
|
|
|
|
|
|
2015-12-30 03:10:41 -04:00
|
|
|
if (_imu._accel_calibrator != NULL && _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];
|
|
|
|
|
|
|
|
//remove rotation
|
|
|
|
cal_sample.rotate_inverse(_imu._board_orientation);
|
|
|
|
|
|
|
|
// remove scale factors
|
|
|
|
const Vector3f &accel_scale = _imu._accel_scale[instance].get();
|
|
|
|
cal_sample.x /= accel_scale.x;
|
|
|
|
cal_sample.y /= accel_scale.y;
|
|
|
|
cal_sample.z /= accel_scale.z;
|
|
|
|
|
|
|
|
//remove offsets
|
|
|
|
cal_sample += _imu._accel_offset[instance].get() * _imu._delta_velocity_dt[instance] ;
|
|
|
|
|
|
|
|
_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,
|
|
|
|
uint64_t sample_us)
|
2015-08-27 16:05:13 -03:00
|
|
|
{
|
2015-09-08 11:42:28 -03:00
|
|
|
float dt;
|
|
|
|
|
AP_InertialSensor: use raw sample rate terminology
In order to avoid confusion between sample rate from sensor and sample rate
from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to
the former.
The changes in the code were basically done with the following commands:
git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g"
git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g"
git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g"
git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g"
git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g"
git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g"
And also with minor changes on indentation and comments.
2015-09-10 09:56:28 -03:00
|
|
|
if (_imu._accel_raw_sample_rates[instance] <= 0) {
|
2015-09-08 11:42:28 -03:00
|
|
|
return;
|
2015-08-27 16:18:42 -03:00
|
|
|
}
|
2015-09-08 11:42:28 -03:00
|
|
|
|
AP_InertialSensor: use raw sample rate terminology
In order to avoid confusion between sample rate from sensor and sample rate
from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to
the former.
The changes in the code were basically done with the following commands:
git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g"
git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g"
git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g"
git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g"
git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g"
git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g"
And also with minor changes on indentation and comments.
2015-09-10 09:56:28 -03:00
|
|
|
dt = 1.0f / _imu._accel_raw_sample_rates[instance];
|
2015-09-08 11:42:28 -03:00
|
|
|
|
|
|
|
_imu.calc_vibration_and_clipping(instance, accel, dt);
|
|
|
|
|
|
|
|
// delta velocity
|
|
|
|
_imu._delta_velocity_acc[instance] += accel * dt;
|
|
|
|
_imu._delta_velocity_acc_dt[instance] += dt;
|
2015-11-15 20:05:20 -04:00
|
|
|
|
|
|
|
_imu._accel_filtered[instance] = _imu._accel_filter[instance].apply(accel);
|
2015-11-21 02:55:51 -04:00
|
|
|
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
|
|
|
|
2015-12-29 13:18:07 -04:00
|
|
|
_imu.set_accel_peak_hold(instance, _imu._accel_filtered[instance]);
|
|
|
|
|
2015-11-15 20:05:20 -04:00
|
|
|
_imu._new_accel_data[instance] = true;
|
2015-11-15 20:58:08 -04:00
|
|
|
|
|
|
|
DataFlash_Class *dataflash = get_dataflash();
|
|
|
|
if (dataflash != NULL) {
|
2015-11-19 23:11:52 -04:00
|
|
|
uint64_t now = AP_HAL::micros64();
|
2015-11-15 20:58:08 -04:00
|
|
|
struct log_ACCEL pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_ACC1_MSG+instance)),
|
|
|
|
time_us : now,
|
|
|
|
sample_us : sample_us?sample_us:now,
|
|
|
|
AccX : accel.x,
|
|
|
|
AccY : accel.y,
|
|
|
|
AccZ : accel.z
|
|
|
|
};
|
|
|
|
dataflash->WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
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
|
|
|
}
|
|
|
|
|
2014-12-29 06:19:35 -04:00
|
|
|
// set accelerometer error_count
|
|
|
|
void AP_InertialSensor_Backend::_set_accel_error_count(uint8_t instance, uint32_t error_count)
|
|
|
|
{
|
|
|
|
_imu._accel_error_count[instance] = error_count;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set gyro error_count
|
|
|
|
void AP_InertialSensor_Backend::_set_gyro_error_count(uint8_t instance, uint32_t error_count)
|
|
|
|
{
|
|
|
|
_imu._gyro_error_count[instance] = error_count;
|
|
|
|
}
|
|
|
|
|
2015-03-11 20:02:36 -03:00
|
|
|
// return the requested sample rate in Hz
|
|
|
|
uint16_t AP_InertialSensor_Backend::get_sample_rate_hz(void) const
|
|
|
|
{
|
|
|
|
// enum can be directly cast to Hz
|
|
|
|
return (uint16_t)_imu._sample_rate;
|
|
|
|
}
|
2015-03-16 23:32:54 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
publish a temperature value for an instance
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::_publish_temperature(uint8_t instance, float temperature)
|
|
|
|
{
|
|
|
|
_imu._temperature[instance] = temperature;
|
|
|
|
}
|
2015-11-15 20:05:20 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
common gyro update function for all backends
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::update_gyro(uint8_t instance)
|
|
|
|
{
|
|
|
|
hal.scheduler->suspend_timer_procs();
|
|
|
|
|
|
|
|
if (_imu._new_gyro_data[instance]) {
|
|
|
|
_publish_gyro(instance, _imu._gyro_filtered[instance]);
|
|
|
|
_imu._new_gyro_data[instance] = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// possibly update filter frequency
|
2015-11-16 02:31:15 -04:00
|
|
|
if (_last_gyro_filter_hz[instance] != _gyro_filter_cutoff()) {
|
2015-11-15 20:05:20 -04:00
|
|
|
_imu._gyro_filter[instance].set_cutoff_frequency(_gyro_raw_sample_rate(instance), _gyro_filter_cutoff());
|
2015-11-16 02:31:15 -04:00
|
|
|
_last_gyro_filter_hz[instance] = _gyro_filter_cutoff();
|
2015-11-15 20:05:20 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
hal.scheduler->resume_timer_procs();
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
common accel update function for all backends
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::update_accel(uint8_t instance)
|
|
|
|
{
|
|
|
|
hal.scheduler->suspend_timer_procs();
|
|
|
|
|
|
|
|
if (_imu._new_accel_data[instance]) {
|
|
|
|
_publish_accel(instance, _imu._accel_filtered[instance]);
|
|
|
|
_imu._new_accel_data[instance] = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// possibly update filter frequency
|
2015-11-16 02:31:15 -04:00
|
|
|
if (_last_accel_filter_hz[instance] != _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());
|
2015-11-16 02:31:15 -04:00
|
|
|
_last_accel_filter_hz[instance] = _accel_filter_cutoff();
|
2015-11-15 20:05:20 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
hal.scheduler->resume_timer_procs();
|
|
|
|
}
|