2014-10-14 01:48:33 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include "AP_InertialSensor.h"
|
|
|
|
#include "AP_InertialSensor_Backend.h"
|
|
|
|
|
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
|
|
|
*/
|
|
|
|
|
|
|
|
// 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
|
|
|
|
|
|
|
// apply offsets
|
2015-02-17 02:54:17 -04:00
|
|
|
accel -= _imu._accel_offset[instance];
|
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
|
|
|
}
|
|
|
|
|
|
|
|
void AP_InertialSensor_Backend::_publish_delta_angle(uint8_t instance, const Vector3f &delta_angle)
|
|
|
|
{
|
|
|
|
// publish delta angle
|
|
|
|
_imu._delta_angle[instance] = delta_angle;
|
|
|
|
_imu._delta_angle_valid[instance] = true;
|
|
|
|
}
|
|
|
|
|
2014-10-14 01:48:33 -03:00
|
|
|
/*
|
|
|
|
rotate gyro vector and add the gyro offset
|
|
|
|
*/
|
2015-02-17 02:54:17 -04:00
|
|
|
void AP_InertialSensor_Backend::_publish_gyro(uint8_t instance, const Vector3f &gyro, bool rotate_and_correct)
|
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-02-17 02:54:17 -04:00
|
|
|
|
|
|
|
if (rotate_and_correct) {
|
|
|
|
_rotate_and_correct_gyro(instance, _imu._gyro[instance]);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-03-21 17:18:58 -03:00
|
|
|
void AP_InertialSensor_Backend::_publish_delta_velocity(uint8_t instance, const Vector3f &delta_velocity, float dt)
|
2015-02-17 02:54:17 -04:00
|
|
|
{
|
|
|
|
// publish delta velocity
|
|
|
|
_imu._delta_velocity[instance] = delta_velocity;
|
2015-03-21 17:18:58 -03:00
|
|
|
_imu._delta_velocity_dt[instance] = dt;
|
2015-02-17 02:54:17 -04:00
|
|
|
_imu._delta_velocity_valid[instance] = true;
|
2014-10-14 01:48:33 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
rotate accel vector, scale and add the accel offset
|
|
|
|
*/
|
2015-02-17 02:54:17 -04:00
|
|
|
void AP_InertialSensor_Backend::_publish_accel(uint8_t instance, const Vector3f &accel, bool rotate_and_correct)
|
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-02-17 02:54:17 -04:00
|
|
|
|
|
|
|
if (rotate_and_correct) {
|
|
|
|
_rotate_and_correct_accel(instance, _imu._accel[instance]);
|
|
|
|
}
|
2014-10-14 01:48:33 -03:00
|
|
|
}
|
2014-10-16 17:52:21 -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;
|
|
|
|
}
|