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"
|
2019-01-18 00:23:42 -04:00
|
|
|
#include <AP_Logger/AP_Logger.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>
|
2017-04-30 21:53:41 -03:00
|
|
|
#include <stdio.h>
|
2018-02-09 04:10:30 -04:00
|
|
|
#endif
|
2017-04-30 21:53:41 -03:00
|
|
|
|
|
|
|
#define SENSOR_RATE_DEBUG 0
|
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) :
|
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);
|
2017-04-30 21:53:41 -03:00
|
|
|
#if SENSOR_RATE_DEBUG
|
|
|
|
printf("RATE: %.1f should be %.1f\n", observed_rate_hz, rate_hz);
|
|
|
|
#endif
|
2019-04-04 19:07:44 -03:00
|
|
|
float filter_constant = 0.98f;
|
|
|
|
float upper_limit = 1.05f;
|
|
|
|
float lower_limit = 0.95f;
|
2017-05-01 00:15:41 -03:00
|
|
|
if (AP_HAL::millis() < 30000) {
|
|
|
|
// 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
|
|
|
// 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
|
2018-03-08 22:26:39 -04:00
|
|
|
if (_imu._board_orientation == ROTATION_CUSTOM && _imu._custom_rotation) {
|
|
|
|
accel = *_imu._custom_rotation * accel;
|
|
|
|
} else {
|
|
|
|
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]);
|
|
|
|
|
2015-03-10 04:05:41 -03:00
|
|
|
// 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];
|
2016-11-03 06:19:04 -03:00
|
|
|
|
2018-03-08 22:26:39 -04:00
|
|
|
if (_imu._board_orientation == ROTATION_CUSTOM && _imu._custom_rotation) {
|
|
|
|
gyro = *_imu._custom_rotation * gyro;
|
|
|
|
} else {
|
|
|
|
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
|
|
|
|
|
|
|
// 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;
|
|
|
|
|
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]);
|
|
|
|
|
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;
|
2017-04-30 21:53:41 -03:00
|
|
|
} else {
|
|
|
|
// don't accept below 100Hz
|
|
|
|
if (_imu._gyro_raw_sample_rates[instance] < 100) {
|
|
|
|
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];
|
|
|
|
}
|
|
|
|
_imu._gyro_last_sample_us[instance] = sample_us;
|
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
|
|
|
|
if (hal.opticalflow)
|
|
|
|
hal.opticalflow->push_gyro(gyro.x, gyro.y, dt);
|
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);
|
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;
|
2015-11-15 20:05:20 -04:00
|
|
|
|
2016-11-03 21:06:19 -03:00
|
|
|
_imu._gyro_filtered[instance] = _imu._gyro_filter[instance].apply(gyro);
|
|
|
|
if (_imu._gyro_filtered[instance].is_nan() || _imu._gyro_filtered[instance].is_inf()) {
|
|
|
|
_imu._gyro_filter[instance].reset();
|
|
|
|
}
|
|
|
|
_imu._new_gyro_data[instance] = true;
|
2015-11-21 02:55:51 -04:00
|
|
|
}
|
2015-11-15 20:05:20 -04:00
|
|
|
|
2017-09-08 11:42:57 -03:00
|
|
|
log_gyro_raw(instance, sample_us, gyro);
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gyro)
|
|
|
|
{
|
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()) {
|
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
|
|
|
|
};
|
2019-02-11 04:32:47 -04:00
|
|
|
logger->WriteBlock(&pkt, sizeof(pkt));
|
2017-10-03 20:44:07 -03:00
|
|
|
} else {
|
2018-03-18 20:28:33 -03:00
|
|
|
if (!_imu.batchsampler.doing_sensor_rate_logging()) {
|
|
|
|
_imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, sample_us, gyro);
|
|
|
|
}
|
2015-11-15 20:58:08 -04:00
|
|
|
}
|
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
|
|
|
|
|
|
|
// 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
|
|
|
|
|
|
|
|
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];
|
|
|
|
|
|
|
|
//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;
|
2016-11-03 06:19:04 -03:00
|
|
|
|
2015-07-20 17:25:40 -03:00
|
|
|
//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,
|
2016-08-31 01:56:27 -03:00
|
|
|
uint64_t sample_us,
|
|
|
|
bool fsync_set)
|
2015-08-27 16:05:13 -03:00
|
|
|
{
|
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]);
|
|
|
|
|
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;
|
2017-04-30 21:53:41 -03:00
|
|
|
} else {
|
|
|
|
// don't accept below 100Hz
|
|
|
|
if (_imu._accel_raw_sample_rates[instance] < 100) {
|
|
|
|
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];
|
|
|
|
}
|
|
|
|
_imu._accel_last_sample_us[instance] = sample_us;
|
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);
|
|
|
|
|
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
|
|
|
|
2017-09-08 11:42:57 -03:00
|
|
|
log_accel_raw(instance, sample_us, accel);
|
|
|
|
}
|
|
|
|
|
2018-03-18 20:28:33 -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
|
|
|
{
|
2018-03-18 20:28:33 -03:00
|
|
|
if (!_imu.batchsampler.doing_sensor_rate_logging()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2018-03-07 04:09:15 -04:00
|
|
|
_imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_ACCEL, AP_HAL::micros64(), accel);
|
|
|
|
}
|
|
|
|
|
2018-03-18 20:28:33 -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
|
|
|
{
|
2018-03-18 20:28:33 -03:00
|
|
|
if (!_imu.batchsampler.doing_sensor_rate_logging()) {
|
|
|
|
return;
|
|
|
|
}
|
2018-03-07 04:09:15 -04:00
|
|
|
_imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, AP_HAL::micros64(), gyro);
|
|
|
|
}
|
|
|
|
|
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)
|
|
|
|
{
|
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()) {
|
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
|
|
|
|
};
|
2019-02-11 04:32:47 -04:00
|
|
|
logger->WriteBlock(&pkt, sizeof(pkt));
|
2017-10-03 20:44:07 -03:00
|
|
|
} else {
|
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);
|
|
|
|
}
|
2015-11-15 20:58:08 -04:00
|
|
|
}
|
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;
|
|
|
|
}
|
|
|
|
|
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-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;
|
2016-06-15 05:02:12 -03:00
|
|
|
|
|
|
|
/* give the temperature to the control loop in order to keep it constant*/
|
|
|
|
if (instance == 0) {
|
|
|
|
hal.util->set_imu_temp(temperature);
|
|
|
|
}
|
2015-03-16 23:32:54 -03:00
|
|
|
}
|
2015-11-15 20:05:20 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
common gyro update function for all backends
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::update_gyro(uint8_t instance)
|
|
|
|
{
|
2018-10-11 20:35:03 -03:00
|
|
|
WITH_SEMAPHORE(_sem);
|
2015-11-15 20:05:20 -04:00
|
|
|
|
|
|
|
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
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
common accel update function for all backends
|
|
|
|
*/
|
|
|
|
void AP_InertialSensor_Backend::update_accel(uint8_t instance)
|
|
|
|
{
|
2018-10-11 20:35:03 -03:00
|
|
|
WITH_SEMAPHORE(_sem);
|
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;
|
|
|
|
}
|
|
|
|
|
|
|
|
// 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
|
|
|
}
|
|
|
|
}
|
2017-06-27 01:42:45 -03:00
|
|
|
|
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
|
|
|
}
|
2018-02-09 04:10:30 -04:00
|
|
|
|