2012-07-28 02:17:38 -03:00
/*
2012-08-17 02:40:30 -03:00
* AP_AHRS_MPU6000 . cpp
*
* AHRS system using MPU6000 ' s internal calculations
*
* Adapted for the general ArduPilot AHRS interface by Andrew Tridgell
*
* This library is free software ; you can redistribute it and / or
* modify it under the terms of the GNU Lesser General Public License
* as published by the Free Software Foundation ; either version 2.1
* of the License , or ( at your option ) any later version .
*/
2012-07-28 02:17:38 -03:00
# include <FastSerial.h>
# include <AP_AHRS.h>
// this is the speed in cm/s above which we first get a yaw lock with
// the GPS
# define GPS_SPEED_MIN 300
// this is the speed in cm/s at which we stop using drift correction
// from the GPS and wait for the ground speed to get above GPS_SPEED_MIN
# define GPS_SPEED_RESET 100
// the limit (in degrees/second) beyond which we stop integrating
// omega_I. At larger spin rates the DCM PI controller can get 'dizzy'
// which results in false gyro drift. See
// http://gentlenav.googlecode.com/files/fastRotations.pdf
# define SPIN_RATE_LIMIT 20
void
2012-09-29 01:51:21 -03:00
AP_AHRS_MPU6000 : : init ( AP_PeriodicProcess * scheduler )
2012-07-28 02:17:38 -03:00
{
2012-09-29 01:51:21 -03:00
bool timer_running = false ;
// suspend timer so interrupts on spi bus do not interfere with communication to mpu6000
if ( scheduler ! = NULL ) {
timer_running = scheduler - > running ( ) ;
scheduler - > suspend_timer ( ) ;
}
2012-08-17 02:40:30 -03:00
_mpu6000 - > dmp_init ( ) ;
push_gains_to_dmp ( ) ;
2012-11-05 00:29:00 -04:00
_mpu6000 - > push_gyro_offsets_to_dmp ( ) ;
2012-09-29 01:51:21 -03:00
// restart timer
if ( timer_running ) {
scheduler - > resume_timer ( ) ;
}
2012-07-28 02:17:38 -03:00
} ;
// run a full MPU6000 update round
void
AP_AHRS_MPU6000 : : update ( void )
{
2012-08-17 02:40:30 -03:00
float delta_t ;
2012-09-29 12:21:18 -03:00
// tell the IMU to grab some data.
if ( ! _secondary_ahrs ) {
2012-11-05 00:29:00 -04:00
_ins - > update ( ) ;
2012-09-29 12:21:18 -03:00
}
2012-07-28 02:17:38 -03:00
2012-08-17 02:40:30 -03:00
// ask the IMU how much time this sensor reading represents
2012-11-05 00:29:00 -04:00
delta_t = _ins - > get_delta_time ( ) ;
2012-07-28 02:17:38 -03:00
2012-08-17 02:40:30 -03:00
// convert the quaternions into a DCM matrix
_mpu6000 - > quaternion . rotation_matrix ( _dcm_matrix ) ;
2012-07-28 02:17:38 -03:00
2012-08-17 02:40:30 -03:00
// we run the gyro bias correction using gravity vector algorithm
drift_correction ( delta_t ) ;
2012-07-28 02:17:38 -03:00
2012-08-17 02:40:30 -03:00
// Calculate pitch, roll, yaw for stabilization and navigation
euler_angles ( ) ;
2012-07-28 02:17:38 -03:00
}
// wrap_PI - ensure an angle (expressed in radians) is between -PI and PI
// TO-DO: should remove and replace with more standard functions
float AP_AHRS_MPU6000 : : wrap_PI ( float angle_in_radians )
{
2012-08-17 02:40:30 -03:00
if ( angle_in_radians > M_PI ) {
return ( angle_in_radians - 2 * M_PI ) ;
}
else if ( angle_in_radians < - M_PI ) {
return ( angle_in_radians + 2 * M_PI ) ;
}
else {
return ( angle_in_radians ) ;
}
2012-07-28 02:17:38 -03:00
}
// Function to correct the gyroX and gyroY bias (roll and pitch) using the gravity vector from accelerometers
// We use the internal chip axis definition to make the bias correction because both sensors outputs (gyros and accels)
// are in chip axis definition
void AP_AHRS_MPU6000 : : drift_correction ( float deltat )
{
2012-08-17 02:40:30 -03:00
float errorRollPitch [ 2 ] ;
// Get current values for gyros
2012-11-05 00:29:00 -04:00
_accel_vector = _ins - > get_accel ( ) ;
2012-08-17 02:40:30 -03:00
// We take the accelerometer readings and cumulate to average them and obtain the gravity vector
_accel_filtered + = _accel_vector ;
_accel_filtered_samples + + ;
_gyro_bias_from_gravity_counter + + ;
// We make the bias calculation and correction at a lower rate (GYRO_BIAS_FROM_GRAVITY_RATE)
if ( _gyro_bias_from_gravity_counter = = GYRO_BIAS_FROM_GRAVITY_RATE ) {
_gyro_bias_from_gravity_counter = 0 ;
_accel_filtered / = _accel_filtered_samples ; // average
// Adjust ground reference : Accel Cross Gravity to obtain the error between gravity from accels and gravity from attitude solution
// errorRollPitch are in Accel LSB units
errorRollPitch [ 0 ] = _accel_filtered . y * _dcm_matrix . c . z + _accel_filtered . z * _dcm_matrix . c . x ;
errorRollPitch [ 1 ] = - _accel_filtered . z * _dcm_matrix . c . y - _accel_filtered . x * _dcm_matrix . c . z ;
errorRollPitch [ 0 ] * = deltat * 1000 ;
errorRollPitch [ 1 ] * = deltat * 1000 ;
// we limit to maximum gyro drift rate on each axis
float drift_limit = _mpu6000 - > get_gyro_drift_rate ( ) * deltat / _gyro_bias_from_gravity_gain ; //0.65*0.04 / 0.005 = 5.2
errorRollPitch [ 0 ] = constrain ( errorRollPitch [ 0 ] , - drift_limit , drift_limit ) ;
errorRollPitch [ 1 ] = constrain ( errorRollPitch [ 1 ] , - drift_limit , drift_limit ) ;
// We correct gyroX and gyroY bias using the error vector
_gyro_bias [ 0 ] + = errorRollPitch [ 0 ] * _gyro_bias_from_gravity_gain ;
_gyro_bias [ 1 ] + = errorRollPitch [ 1 ] * _gyro_bias_from_gravity_gain ;
// TO-DO: fix this. Currently it makes the roll and pitch drift more!
// If bias values are greater than 1 LSB we update the hardware offset registers
if ( fabs ( _gyro_bias [ 0 ] ) > 1.0 ) {
//_mpu6000->set_gyro_offsets(-1*(int)_gyro_bias[0],0,0);
//_mpu6000->set_gyro_offsets(0,-1*(int)_gyro_bias[0],0);
//_gyro_bias[0] -= (int)_gyro_bias[0]; // we remove the part that we have already corrected on registers...
}
if ( fabs ( _gyro_bias [ 1 ] ) > 1.0 ) {
//_mpu6000->set_gyro_offsets(-1*(int)_gyro_bias[1],0,0);
//_gyro_bias[1] -= (int)_gyro_bias[1];
}
// Reset the accelerometer variables
_accel_filtered . x = 0 ;
_accel_filtered . y = 0 ;
_accel_filtered . z = 0 ;
_accel_filtered_samples = 0 ;
}
// correct the yaw
drift_correction_yaw ( ) ;
2012-07-28 02:17:38 -03:00
}
/*
2012-08-17 02:40:30 -03:00
* reset the DCM matrix and omega . Used on ground start , and on
* extreme errors in the matrix
2012-07-28 02:17:38 -03:00
*/
void
AP_AHRS_MPU6000 : : reset ( bool recover_eulers )
{
2012-08-17 02:40:30 -03:00
// if the caller wants us to try to recover to the current
// attitude then calculate the dcm matrix from the current
// roll/pitch/yaw values
if ( recover_eulers & & ! isnan ( roll ) & & ! isnan ( pitch ) & & ! isnan ( yaw ) ) {
_dcm_matrix . from_euler ( roll , pitch , yaw ) ;
} else {
// otherwise make it flat
_dcm_matrix . from_euler ( 0 , 0 , 0 ) ;
}
2012-07-28 02:17:38 -03:00
}
// push offsets down from IMU to INS (required so MPU6000 can perform it's own attitude estimation)
void
AP_AHRS_MPU6000 : : push_offsets_to_ins ( )
{
2012-08-17 02:40:30 -03:00
// push down gyro offsets (TO-DO: why are x and y offsets are reversed?!)
2012-11-05 00:29:00 -04:00
_mpu6000 - > push_gyro_offsets_to_dmp ( ) ;
2012-08-17 02:40:30 -03:00
// push down accelerometer offsets (TO-DO: why are x and y offsets are reversed?!)
2012-11-05 00:29:00 -04:00
_mpu6000 - > push_accel_offsets_to_dmp ( ) ;
2012-07-28 02:17:38 -03:00
}
void
AP_AHRS_MPU6000 : : push_gains_to_dmp ( )
{
2012-08-17 02:40:30 -03:00
uint8_t gain ;
if ( _kp . get ( ) > = 1.0 ) {
gain = 0xFF ;
} else if ( _kp . get ( ) < = 0.0 ) {
gain = 0x00 ;
} else {
gain = ( uint8_t ) ( ( float ) 0xFF * _kp . get ( ) ) ;
}
_mpu6000 - > dmp_set_sensor_fusion_accel_gain ( gain ) ;
2012-07-28 02:17:38 -03:00
}
// produce a yaw error value. The returned value is proportional
// to sin() of the current heading error in earth frame
float
AP_AHRS_MPU6000 : : yaw_error_compass ( void )
{
2012-08-17 02:40:30 -03:00
Vector3f mag = Vector3f ( _compass - > mag_x , _compass - > mag_y , _compass - > mag_z ) ;
// get the mag vector in the earth frame
Vector3f rb = _dcm_matrix * mag ;
2012-07-28 02:17:38 -03:00
2012-08-17 02:40:30 -03:00
rb . normalize ( ) ;
if ( rb . is_inf ( ) ) {
// not a valid vector
return 0.0 ;
}
2012-07-28 02:17:38 -03:00
2012-08-17 02:40:30 -03:00
// get the earths magnetic field (only X and Y components needed)
Vector3f mag_earth = Vector3f ( cos ( _compass - > get_declination ( ) ) ,
sin ( _compass - > get_declination ( ) ) , 0 ) ;
2012-07-28 02:17:38 -03:00
2012-08-17 02:40:30 -03:00
// calculate the error term in earth frame
Vector3f error = rb % mag_earth ;
2012-07-28 02:17:38 -03:00
2012-08-17 02:40:30 -03:00
return error . z ;
2012-07-28 02:17:38 -03:00
}
//
// drift_correction_yaw - yaw drift correction using the compass
2012-09-29 12:21:18 -03:00
// we have no way to update the dmp with it's actual heading from our compass
// instead we use the yaw_corrected variable to hold what we think is the real heading
// we also record what the dmp said it's last heading was in the yaw_last_uncorrected variable so that on the next iteration we can add the change in yaw to our estimate
2012-07-28 02:17:38 -03:00
//
void
AP_AHRS_MPU6000 : : drift_correction_yaw ( void )
{
2012-08-17 02:40:30 -03:00
static float yaw_corrected = HEADING_UNKNOWN ;
2012-09-29 12:21:18 -03:00
static float last_dmp_yaw = HEADING_UNKNOWN ;
float dmp_roll , dmp_pitch , dmp_yaw ; // roll pitch and yaw values from dmp
float yaw_delta ; // change in yaw according to dmp
float yaw_error ; // difference between heading and corrected yaw
2012-08-17 02:40:30 -03:00
static float heading ;
2012-09-29 12:21:18 -03:00
// get uncorrected yaw values from dmp
_mpu6000 - > quaternion . to_euler ( & dmp_roll , & dmp_pitch , & dmp_yaw ) ;
2012-08-17 02:40:30 -03:00
2012-09-29 12:21:18 -03:00
// initialise headings on first iteration
if ( yaw_corrected = = HEADING_UNKNOWN ) {
yaw_corrected = dmp_yaw ;
last_dmp_yaw = dmp_yaw ;
2012-08-17 02:40:30 -03:00
}
2012-09-29 12:21:18 -03:00
// change in yaw according to dmp
yaw_delta = wrap_PI ( dmp_yaw - last_dmp_yaw ) ;
yaw_corrected = wrap_PI ( yaw_corrected + yaw_delta ) ;
last_dmp_yaw = dmp_yaw ;
// rebuild dcm matrix
_dcm_matrix . from_euler ( dmp_roll , dmp_pitch , yaw_corrected ) ;
2012-08-17 02:40:30 -03:00
// if we have new compass data
2012-09-29 12:21:18 -03:00
if ( _compass & & _compass - > use_for_yaw ( ) ) {
if ( _compass - > last_update ! = _compass_last_update ) {
2012-08-17 02:40:30 -03:00
_compass_last_update = _compass - > last_update ;
heading = _compass - > calculate_heading ( _dcm_matrix ) ;
2012-09-29 12:21:18 -03:00
// if this is the first good compass reading then set yaw to this heading
2012-08-17 02:40:30 -03:00
if ( ! _have_initial_yaw ) {
_have_initial_yaw = true ;
2012-09-29 12:21:18 -03:00
yaw_corrected = wrap_PI ( heading ) ;
2012-08-17 02:40:30 -03:00
}
2012-09-29 12:21:18 -03:00
// yaw correction based on compass
//yaw_error = yaw_error_compass();
yaw_error = wrap_PI ( heading - yaw_corrected ) ;
2012-08-17 02:40:30 -03:00
2012-09-29 12:21:18 -03:00
// shift the corrected yaw towards the compass heading a bit
yaw_corrected + = wrap_PI ( yaw_error * _kp_yaw . get ( ) * 0.1 ) ;
2012-08-17 02:40:30 -03:00
2012-09-29 12:21:18 -03:00
// rebuild the dcm matrix yet again
_dcm_matrix . from_euler ( dmp_roll , dmp_pitch , yaw_corrected ) ;
}
2012-08-17 02:40:30 -03:00
}
2012-07-28 02:17:38 -03:00
}
// calculate the euler angles which will be used for high level
// navigation control
void
AP_AHRS_MPU6000 : : euler_angles ( void )
{
2012-08-17 02:40:30 -03:00
_dcm_matrix . to_euler ( & roll , & pitch , & yaw ) ;
//quaternion.to_euler(&roll, &pitch, &yaw); // cannot use this because the quaternion is not correct for yaw drift
2012-07-28 02:17:38 -03:00
2012-08-17 02:40:30 -03:00
roll_sensor = degrees ( roll ) * 100 ;
pitch_sensor = degrees ( pitch ) * 100 ;
yaw_sensor = degrees ( yaw ) * 100 ;
2012-07-28 02:17:38 -03:00
2012-08-17 02:40:30 -03:00
if ( yaw_sensor < 0 )
yaw_sensor + = 36000 ;
2012-07-28 02:17:38 -03:00
}
/* reporting of DCM state for MAVLink */
// average error_roll_pitch since last call
float AP_AHRS_MPU6000 : : get_error_rp ( void )
{
2012-08-17 02:40:30 -03:00
// not yet supported with DMP
return 0.0 ;
2012-07-28 02:17:38 -03:00
}
// average error_yaw since last call
float AP_AHRS_MPU6000 : : get_error_yaw ( void )
{
2012-08-17 02:40:30 -03:00
// not yet supported with DMP
return 0.0 ;
2012-07-28 02:17:38 -03:00
}