2010-10-30 13:17:16 -03:00
/*
2012-08-21 23:19:51 -03:00
* APM_AHRS_DCM . cpp
*
* AHRS system using DCM matrices
*
2019-02-11 04:15:24 -04:00
* Based on DCM code by Doug Weibel , Jordi Munoz and Jose Julio . DIYDrones . com
2012-08-21 23:19:51 -03:00
*
* Adapted for the general ArduPilot AHRS interface by Andrew Tridgell
2013-08-26 03:55:30 -03:00
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
2015-09-23 04:29:43 -03:00
2013-08-26 03:55:30 -03:00
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
2012-08-21 23:19:51 -03:00
*/
2015-08-11 03:28:42 -03:00
# include "AP_AHRS.h"
# include <AP_HAL/AP_HAL.h>
2018-10-10 00:27:00 -03:00
# include <GCS_MAVLink/GCS.h>
2019-06-14 00:15:53 -03:00
# include <AP_GPS/AP_GPS.h>
2019-06-26 23:37:09 -03:00
# include <AP_Baro/AP_Baro.h>
2022-02-25 01:06:27 -04:00
# include <AP_Compass/AP_Compass.h>
2022-01-30 01:48:06 -04:00
# include <AP_Logger/AP_Logger.h>
2022-10-27 22:38:06 -03:00
# include <AP_Vehicle/AP_Vehicle_Type.h>
2012-11-14 12:10:15 -04:00
extern const AP_HAL : : HAL & hal ;
2014-03-30 08:00:25 -03:00
// this is the speed in m/s above which we first get a yaw lock with
2012-02-24 20:30:59 -04:00
// the GPS
2014-03-30 08:00:25 -03:00
# define GPS_SPEED_MIN 3
2010-10-24 15:37:10 -03:00
2012-06-27 22:09:22 -03:00
// 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
2014-10-28 08:22:48 -03:00
// reset the current gyro drift estimate
// should be called if gyro offsets are recalculated
void
AP_AHRS_DCM : : reset_gyro_drift ( void )
{
_omega_I . zero ( ) ;
_omega_I_sum . zero ( ) ;
_omega_I_sum_time = 0 ;
}
2012-04-16 07:51:46 -03:00
2019-04-20 07:02:46 -03:00
/* if this was a watchdog reset then get home from backup registers */
2021-07-24 20:08:28 -03:00
void AP_AHRS : : load_watchdog_home ( )
2019-04-20 07:02:46 -03:00
{
2019-05-15 01:12:15 -03:00
const AP_HAL : : Util : : PersistentData & pd = hal . util - > persistent_data ;
2019-05-09 04:49:55 -03:00
if ( hal . util - > was_watchdog_reset ( ) & & ( pd . home_lat ! = 0 | | pd . home_lon ! = 0 ) ) {
_home . lat = pd . home_lat ;
_home . lng = pd . home_lon ;
_home . set_alt_cm ( pd . home_alt_cm , Location : : AltFrame : : ABSOLUTE ) ;
2019-04-20 07:02:46 -03:00
_home_is_set = true ;
_home_locked = true ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Restored watchdog home " ) ;
}
}
2021-08-18 07:20:46 -03:00
2012-03-07 00:09:17 -04:00
// run a full DCM update round
2010-10-24 15:37:10 -03:00
void
2021-08-18 07:20:46 -03:00
AP_AHRS_DCM : : update ( )
2010-10-24 15:37:10 -03:00
{
2020-10-16 04:03:11 -03:00
AP_InertialSensor & _ins = AP : : ins ( ) ;
2012-08-21 23:19:51 -03:00
// ask the IMU how much time this sensor reading represents
2020-10-16 04:03:11 -03:00
const float delta_t = _ins . get_delta_time ( ) ;
2011-09-15 00:04:08 -03:00
2012-11-13 00:33:10 -04:00
// if the update call took more than 0.2 seconds then discard it,
2015-09-23 04:29:43 -03:00
// otherwise we may move too far. This happens when arming motors
2012-11-13 00:33:10 -04:00
// in ArduCopter
2013-01-10 14:42:24 -04:00
if ( delta_t > 0.2f ) {
2018-10-30 14:16:50 -03:00
memset ( ( void * ) & _ra_sum [ 0 ] , 0 , sizeof ( _ra_sum ) ) ;
2012-11-13 00:33:10 -04:00
_ra_deltat = 0 ;
return ;
}
2012-08-21 23:19:51 -03:00
// Integrate the DCM matrix using gyro inputs
2022-07-26 04:50:35 -03:00
matrix_update ( ) ;
2011-09-11 15:03:55 -03:00
2012-08-21 23:19:51 -03:00
// Normalize the DCM matrix
normalize ( ) ;
2011-09-11 15:03:55 -03:00
2012-08-21 23:19:51 -03:00
// Perform drift correction
drift_correction ( delta_t ) ;
2010-10-24 15:37:10 -03:00
2012-08-21 23:19:51 -03:00
// paranoid check for bad values in the DCM matrix
check_matrix ( ) ;
2010-11-14 22:15:16 -04:00
2021-08-18 07:20:46 -03:00
// calculate the euler angles and DCM matrix which will be used
// for high level navigation control. Apply trim such that a
// positive trim value results in a positive vehicle rotation
// about that axis (ie a negative offset)
_body_dcm_matrix = _dcm_matrix * AP : : ahrs ( ) . get_rotation_vehicle_body_to_autopilot_body ( ) ;
_body_dcm_matrix . to_euler ( & roll , & pitch , & yaw ) ;
2017-04-09 08:17:05 -03:00
2021-10-05 00:08:54 -03:00
// pre-calculate some trig for CPU purposes:
_cos_yaw = cosf ( yaw ) ;
_sin_yaw = sinf ( yaw ) ;
2019-04-21 00:08:29 -03:00
backup_attitude ( ) ;
2021-08-14 00:03:42 -03:00
// remember the last origin for fallback support
IGNORE_RETURN ( AP : : ahrs ( ) . get_origin ( last_origin ) ) ;
2019-04-21 00:08:29 -03:00
}
2021-08-18 07:20:46 -03:00
void AP_AHRS_DCM : : get_results ( AP_AHRS_Backend : : Estimates & results )
{
results . roll_rad = roll ;
results . pitch_rad = pitch ;
results . yaw_rad = yaw ;
results . dcm_matrix = _body_dcm_matrix ;
results . gyro_estimate = _omega ;
results . gyro_drift = _omega_I ;
2022-07-26 21:21:01 -03:00
results . accel_ef = _accel_ef ;
2021-08-18 07:20:46 -03:00
}
2019-04-21 00:08:29 -03:00
/*
2019-05-09 04:49:55 -03:00
backup attitude to persistent_data for use in watchdog reset
2019-04-21 00:08:29 -03:00
*/
void AP_AHRS_DCM : : backup_attitude ( void )
{
2019-05-09 04:49:55 -03:00
AP_HAL : : Util : : PersistentData & pd = hal . util - > persistent_data ;
pd . roll_rad = roll ;
pd . pitch_rad = pitch ;
pd . yaw_rad = yaw ;
2010-11-17 17:20:20 -04:00
}
2011-06-12 20:49:01 -03:00
2012-03-07 00:09:17 -04:00
// update the DCM matrix using only the gyros
2022-07-26 04:50:35 -03:00
void AP_AHRS_DCM : : matrix_update ( void )
2010-10-24 15:37:10 -03:00
{
2022-07-26 04:50:35 -03:00
// use only the primary gyro so our bias estimate is valid, allowing us to return the right filtered gyro
// for rate controllers
const auto & _ins = AP : : ins ( ) ;
Vector3f delta_angle ;
float dangle_dt ;
if ( _ins . get_delta_angle ( delta_angle , dangle_dt ) & & dangle_dt > 0 ) {
_omega = delta_angle / dangle_dt ;
_omega + = _omega_I ;
_dcm_matrix . rotate ( ( _omega + _omega_P + _omega_yaw_P ) * dangle_dt ) ;
}
// now update _omega from the filtered value from the primary IMU. We need to use
// the primary IMU as the notch filters will only be running on one IMU
2012-08-21 23:19:51 -03:00
// note that we do not include the P terms in _omega. This is
// because the spin_rate is calculated from _omega.length(),
// and including the P terms would give positive feedback into
// the _P_gain() calculation, which can lead to a very large P
// value
2022-07-26 04:50:35 -03:00
_omega = _ins . get_gyro ( ) + _omega_I ;
2012-06-27 05:16:41 -03:00
}
2012-06-27 22:09:22 -03:00
2011-12-13 06:32:50 -04:00
/*
2012-08-21 23:19:51 -03:00
* reset the DCM matrix and omega . Used on ground start , and on
* extreme errors in the matrix
2011-12-13 06:32:50 -04:00
*/
void
2012-03-11 04:59:53 -03:00
AP_AHRS_DCM : : reset ( bool recover_eulers )
2011-12-13 06:32:50 -04:00
{
2012-08-21 23:19:51 -03:00
// reset the integration terms
_omega_I . zero ( ) ;
_omega_P . zero ( ) ;
_omega_yaw_P . zero ( ) ;
_omega . zero ( ) ;
// 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
2019-05-09 04:49:55 -03:00
if ( hal . util - > was_watchdog_reset ( ) & & AP_HAL : : millis ( ) < 10000 ) {
2019-05-15 01:12:15 -03:00
const AP_HAL : : Util : : PersistentData & pd = hal . util - > persistent_data ;
2019-05-09 04:49:55 -03:00
roll = pd . roll_rad ;
pitch = pd . pitch_rad ;
yaw = pd . yaw_rad ;
2019-04-21 00:08:29 -03:00
_dcm_matrix . from_euler ( roll , pitch , yaw ) ;
2019-05-09 04:49:55 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Restored watchdog attitude %.0f %.0f %.0f " ,
degrees ( roll ) , degrees ( pitch ) , degrees ( yaw ) ) ;
2019-04-21 00:08:29 -03:00
} else if ( recover_eulers & & ! isnan ( roll ) & & ! isnan ( pitch ) & & ! isnan ( yaw ) ) {
2012-08-21 23:19:51 -03:00
_dcm_matrix . from_euler ( roll , pitch , yaw ) ;
} else {
2015-10-17 18:12:17 -03:00
// Use the measured accel due to gravity to calculate an initial
// roll and pitch estimate
2018-03-10 05:35:03 -04:00
AP_InertialSensor & _ins = AP : : ins ( ) ;
2015-10-17 18:12:17 -03:00
// Get body frame accel vector
2017-12-02 09:02:37 -04:00
Vector3f initAccVec = _ins . get_accel ( ) ;
2015-10-20 19:09:11 -03:00
uint8_t counter = 0 ;
2015-10-17 18:12:17 -03:00
2015-10-20 19:09:11 -03:00
// the first vector may be invalid as the filter starts up
2017-12-04 02:51:52 -04:00
while ( ( initAccVec . length ( ) < 9.0f | | initAccVec . length ( ) > 11 ) & & counter + + < 20 ) {
2015-10-20 19:09:11 -03:00
_ins . wait_for_sample ( ) ;
_ins . update ( ) ;
initAccVec = _ins . get_accel ( ) ;
}
2015-10-17 18:12:17 -03:00
// normalise the acceleration vector
if ( initAccVec . length ( ) > 5.0f ) {
// calculate initial pitch angle
2016-04-16 06:58:46 -03:00
pitch = atan2f ( initAccVec . x , norm ( initAccVec . y , initAccVec . z ) ) ;
2015-10-17 18:12:17 -03:00
// calculate initial roll angle
roll = atan2f ( - initAccVec . y , - initAccVec . z ) ;
} else {
2016-05-12 14:00:11 -03:00
// If we can't use the accel vector, then align flat
2015-10-17 18:12:17 -03:00
roll = 0.0f ;
pitch = 0.0f ;
}
_dcm_matrix . from_euler ( roll , pitch , 0 ) ;
2012-08-21 23:19:51 -03:00
}
2015-04-27 21:26:36 -03:00
2021-10-05 00:08:54 -03:00
// pre-calculate some trig for CPU purposes:
_cos_yaw = cosf ( yaw ) ;
_sin_yaw = sinf ( yaw ) ;
2015-11-19 23:06:21 -04:00
_last_startup_ms = AP_HAL : : millis ( ) ;
2011-12-13 06:32:50 -04:00
}
2010-10-24 15:37:10 -03:00
2012-02-22 17:00:25 -04:00
/*
2012-08-21 23:19:51 -03:00
* check the DCM matrix for pathological values
2012-02-22 17:00:25 -04:00
*/
void
2012-03-11 04:59:53 -03:00
AP_AHRS_DCM : : check_matrix ( void )
2012-02-22 17:00:25 -04:00
{
2012-08-21 23:19:51 -03:00
if ( _dcm_matrix . is_nan ( ) ) {
//Serial.printf("ERROR: DCM matrix NAN\n");
2014-10-14 20:12:50 -03:00
AP_AHRS_DCM : : reset ( true ) ;
2012-08-21 23:19:51 -03:00
return ;
}
// some DCM matrix values can lead to an out of range error in
// the pitch calculation via asin(). These NaN values can
// feed back into the rest of the DCM matrix via the
// error_course value.
2013-01-10 14:42:24 -04:00
if ( ! ( _dcm_matrix . c . x < 1.0f & &
2015-09-23 04:29:43 -03:00
_dcm_matrix . c . x > - 1.0f ) ) {
2012-08-21 23:19:51 -03:00
// We have an invalid matrix. Force a normalisation.
normalize ( ) ;
if ( _dcm_matrix . is_nan ( ) | |
2022-04-15 20:59:48 -03:00
fabsf ( _dcm_matrix . c . x ) > 10.0 ) {
// See Issue #20284: regarding the selection of 10.0 for DCM reset
// This won't be lowered without evidence of an issue or mathematical proof & testing of a lower bound
2012-08-21 23:19:51 -03:00
// normalisation didn't fix the problem! We're
// in real trouble. All we can do is reset
//Serial.printf("ERROR: DCM matrix error. _dcm_matrix.c.x=%f\n",
// _dcm_matrix.c.x);
2014-10-14 20:12:50 -03:00
AP_AHRS_DCM : : reset ( true ) ;
2012-08-21 23:19:51 -03:00
}
}
2012-02-22 17:00:25 -04:00
}
2012-03-07 02:12:42 -04:00
// renormalise one vector component of the DCM matrix
// this will return false if renormalization fails
2012-03-07 00:09:17 -04:00
bool
2012-03-11 04:59:53 -03:00
AP_AHRS_DCM : : renorm ( Vector3f const & a , Vector3f & result )
2010-10-24 15:37:10 -03:00
{
2012-08-21 23:19:51 -03:00
// numerical errors will slowly build up over time in DCM,
// causing inaccuracies. We can keep ahead of those errors
// using the renormalization technique from the DCM IMU paper
// (see equations 18 to 21).
// For APM we don't bother with the taylor expansion
// optimisation from the paper as on our 2560 CPU the cost of
// the sqrt() is 44 microseconds, and the small time saving of
// the taylor expansion is not worth the potential of
// additional error buildup.
// Note that we can get significant renormalisation values
// when we have a larger delta_t due to a glitch eleswhere in
// APM, such as a I2c timeout or a set of EEPROM writes. While
// we would like to avoid these if possible, if it does happen
// we don't want to compound the error by making DCM less
// accurate.
2017-12-02 09:02:37 -04:00
const float renorm_val = 1.0f / a . length ( ) ;
2012-08-21 23:19:51 -03:00
// keep the average for reporting
_renorm_val_sum + = renorm_val ;
_renorm_val_count + + ;
2013-01-10 14:42:24 -04:00
if ( ! ( renorm_val < 2.0f & & renorm_val > 0.5f ) ) {
2012-08-21 23:19:51 -03:00
// this is larger than it should get - log it as a warning
2013-01-10 14:42:24 -04:00
if ( ! ( renorm_val < 1.0e6 f & & renorm_val > 1.0e-6 f ) ) {
2012-08-21 23:19:51 -03:00
// we are getting values which are way out of
// range, we will reset the matrix and hope we
// can recover our attitude using drift
// correction before we hit the ground!
//Serial.printf("ERROR: DCM renormalisation error. renorm_val=%f\n",
// renorm_val);
return false ;
}
}
result = a * renorm_val ;
return true ;
2012-03-07 00:09:17 -04:00
}
/*************************************************
2012-08-21 23:19:51 -03:00
* Direction Cosine Matrix IMU : Theory
* William Premerlani and Paul Bizard
*
* Numerical errors will gradually reduce the orthogonality conditions expressed by equation 5
* to approximations rather than identities . In effect , the axes in the two frames of reference no
* longer describe a rigid body . Fortunately , numerical error accumulates very slowly , so it is a
* simple matter to stay ahead of it .
2019-02-11 04:15:24 -04:00
* We call the process of enforcing the orthogonality conditions : renormalization .
2012-08-21 23:19:51 -03:00
*/
2012-03-07 00:09:17 -04:00
void
2012-03-11 04:59:53 -03:00
AP_AHRS_DCM : : normalize ( void )
2012-03-07 00:09:17 -04:00
{
2017-12-02 09:02:37 -04:00
const float error = _dcm_matrix . a * _dcm_matrix . b ; // eq.18
2012-08-21 23:19:51 -03:00
2017-12-02 09:02:37 -04:00
const Vector3f t0 = _dcm_matrix . a - ( _dcm_matrix . b * ( 0.5f * error ) ) ; // eq.19
const Vector3f t1 = _dcm_matrix . b - ( _dcm_matrix . a * ( 0.5f * error ) ) ; // eq.19
const Vector3f t2 = t0 % t1 ; // c= a x b // eq.20
2012-08-21 23:19:51 -03:00
if ( ! renorm ( t0 , _dcm_matrix . a ) | |
2015-09-23 04:29:43 -03:00
! renorm ( t1 , _dcm_matrix . b ) | |
! renorm ( t2 , _dcm_matrix . c ) ) {
2012-08-21 23:19:51 -03:00
// Our solution is blowing up and we will force back
// to last euler angles
2015-11-19 23:06:21 -04:00
_last_failure_ms = AP_HAL : : millis ( ) ;
2014-10-14 20:12:50 -03:00
AP_AHRS_DCM : : reset ( true ) ;
2012-08-21 23:19:51 -03:00
}
2010-10-24 15:37:10 -03:00
}
2012-03-07 00:09:17 -04:00
2012-06-27 22:09:22 -03:00
// produce a yaw error value. The returned value is proportional
// to sin() of the current heading error in earth frame
float
2021-07-30 01:41:09 -03:00
AP_AHRS_DCM : : yaw_error_compass ( Compass & compass )
2010-10-24 15:37:10 -03:00
{
2021-07-30 01:41:09 -03:00
const Vector3f & mag = compass . get_field ( ) ;
2012-08-21 23:19:51 -03:00
// get the mag vector in the earth frame
2013-05-05 00:51:45 -03:00
Vector2f rb = _dcm_matrix . mulXY ( mag ) ;
2012-08-21 23:19:51 -03:00
2015-05-01 21:02:55 -03:00
if ( rb . length ( ) < FLT_EPSILON ) {
return 0.0f ;
}
2012-08-21 23:19:51 -03:00
rb . normalize ( ) ;
if ( rb . is_inf ( ) ) {
// not a valid vector
2015-04-24 00:25:12 -03:00
return 0.0f ;
2012-08-21 23:19:51 -03:00
}
2012-03-23 02:22:56 -03:00
2013-05-04 12:25:59 -03:00
// update vector holding earths magnetic field (if required)
2021-07-30 01:41:09 -03:00
if ( ! is_equal ( _last_declination , compass . get_declination ( ) ) ) {
_last_declination = compass . get_declination ( ) ;
2013-05-04 12:25:59 -03:00
_mag_earth . x = cosf ( _last_declination ) ;
_mag_earth . y = sinf ( _last_declination ) ;
}
2012-03-23 02:22:56 -03:00
2012-08-21 23:19:51 -03:00
// calculate the error term in earth frame
2013-05-05 00:51:45 -03:00
// calculate the Z component of the cross product of rb and _mag_earth
return rb % _mag_earth ;
2012-06-27 22:09:22 -03:00
}
2012-06-19 01:47:09 -03:00
2012-07-04 03:53:40 -03:00
// the _P_gain raises the gain of the PI controller
2012-08-21 23:19:51 -03:00
// when we are spinning fast. See the fastRotations
// paper from Bill.
2012-06-27 22:09:22 -03:00
float
AP_AHRS_DCM : : _P_gain ( float spin_rate )
{
2013-07-12 23:36:25 -03:00
if ( spin_rate < ToRad ( 50 ) ) {
2013-01-10 14:42:24 -04:00
return 1.0f ;
2012-08-21 23:19:51 -03:00
}
2013-07-12 23:36:25 -03:00
if ( spin_rate > ToRad ( 500 ) ) {
2013-01-10 14:42:24 -04:00
return 10.0f ;
2012-08-21 23:19:51 -03:00
}
2013-07-12 23:36:25 -03:00
return spin_rate / ToRad ( 50 ) ;
2012-06-27 22:09:22 -03:00
}
2012-06-19 01:47:09 -03:00
2014-01-18 03:18:12 -04:00
// _yaw_gain reduces the gain of the PI controller applied to heading errors
// when observability from change of velocity is good (eg changing speed or turning)
// This reduces unwanted roll and pitch coupling due to compass errors for planes.
2015-09-23 04:29:43 -03:00
// High levels of noise on _accel_ef will cause the gain to drop and could lead to
2014-01-18 03:18:12 -04:00
// increased heading drift during straight and level flight, however some gain is
2015-09-23 04:29:43 -03:00
// always available. TODO check the necessity of adding adjustable acc threshold
2014-01-18 03:18:12 -04:00
// and/or filtering accelerations before getting magnitude
float
2014-02-26 18:41:28 -04:00
AP_AHRS_DCM : : _yaw_gain ( void ) const
2014-01-18 03:18:12 -04:00
{
2022-07-26 21:21:01 -03:00
const float VdotEFmag = _accel_ef . xy ( ) . length ( ) ;
2021-09-11 07:29:48 -03:00
2014-01-18 03:18:12 -04:00
if ( VdotEFmag < = 4.0f ) {
return 0.2f * ( 4.5f - VdotEFmag ) ;
}
return 0.1f ;
}
2012-08-11 02:55:53 -03:00
// return true if we have and should use GPS
2013-07-07 22:25:40 -03:00
bool AP_AHRS_DCM : : have_gps ( void ) const
2012-08-11 02:55:53 -03:00
{
2021-01-18 01:32:37 -04:00
if ( AP : : gps ( ) . status ( ) < = AP_GPS : : NO_FIX | | _gps_use = = GPSUse : : Disable ) {
2012-08-21 23:19:51 -03:00
return false ;
}
return true ;
2012-08-11 02:55:53 -03:00
}
2015-04-27 21:26:36 -03:00
/*
when we are getting the initial attitude we want faster gains so
that if the board starts upside down we quickly approach the right
attitude .
We don ' t want to keep those high gains for too long though as high P
gains cause slow gyro offset learning . So we keep the high gains for
a maximum of 20 seconds
*/
bool AP_AHRS_DCM : : use_fast_gains ( void ) const
{
2015-11-19 23:06:21 -04:00
return ! hal . util - > get_soft_armed ( ) & & ( AP_HAL : : millis ( ) - _last_startup_ms ) < 20000U ;
2015-04-27 21:26:36 -03:00
}
2013-03-28 23:48:25 -03:00
// return true if we should use the compass for yaw correction
2013-10-21 23:06:27 -03:00
bool AP_AHRS_DCM : : use_compass ( void )
2013-03-28 23:48:25 -03:00
{
2021-07-30 01:41:09 -03:00
const Compass & compass = AP : : compass ( ) ;
2021-07-25 21:32:10 -03:00
2021-07-30 01:41:09 -03:00
if ( ! compass . use_for_yaw ( ) ) {
2013-03-28 23:48:25 -03:00
// no compass available
return false ;
}
2021-08-11 09:11:54 -03:00
if ( ! AP : : ahrs ( ) . get_fly_forward ( ) | | ! have_gps ( ) ) {
2013-03-28 23:48:25 -03:00
// we don't have any alterative to the compass
return true ;
}
2017-12-01 19:50:46 -04:00
if ( AP : : gps ( ) . ground_speed ( ) < GPS_SPEED_MIN ) {
2013-03-28 23:48:25 -03:00
// we are not going fast enough to use the GPS
return true ;
}
// if the current yaw differs from the GPS yaw by more than 45
// degrees and the estimated wind speed is less than 80% of the
// ground speed, then switch to GPS navigation. This will help
// prevent flyaways with very bad compass offsets
2021-08-18 07:20:46 -03:00
const float error = fabsf ( wrap_180 ( degrees ( yaw ) - AP : : gps ( ) . ground_course ( ) ) ) ;
if ( error > 45 & & _wind . length ( ) < AP : : gps ( ) . ground_speed ( ) * 0.8f ) {
2015-11-19 23:06:21 -04:00
if ( AP_HAL : : millis ( ) - _last_consistent_heading > 2000 ) {
2013-10-21 23:06:27 -03:00
// start using the GPS for heading if the compass has been
// inconsistent with the GPS for 2 seconds
return false ;
}
} else {
2015-11-19 23:06:21 -04:00
_last_consistent_heading = AP_HAL : : millis ( ) ;
2013-03-28 23:48:25 -03:00
}
// use the compass
2015-09-23 04:29:43 -03:00
return true ;
2013-03-28 23:48:25 -03:00
}
2020-03-31 22:08:54 -03:00
// return the quaternion defining the rotation from NED to XYZ (body) axes
bool AP_AHRS_DCM : : get_quaternion ( Quaternion & quat ) const
{
quat . from_rotation_matrix ( _dcm_matrix ) ;
return true ;
}
2012-06-27 22:09:22 -03:00
// yaw drift correction using the compass or GPS
// this function prodoces the _omega_yaw_P vector, and also
// contributes to the _omega_I.z long term yaw drift estimate
void
AP_AHRS_DCM : : drift_correction_yaw ( void )
{
2012-08-21 23:19:51 -03:00
bool new_value = false ;
float yaw_error ;
float yaw_deltat ;
2017-12-01 19:50:46 -04:00
const AP_GPS & _gps = AP : : gps ( ) ;
2021-07-25 21:32:10 -03:00
Compass & compass = AP : : compass ( ) ;
2021-07-30 01:41:09 -03:00
if ( compass . is_calibrating ( ) ) {
2018-07-16 05:18:31 -03:00
// don't do any yaw correction while calibrating
return ;
}
2014-10-14 20:12:50 -03:00
if ( AP_AHRS_DCM : : use_compass ( ) ) {
2013-06-24 23:43:53 -03:00
/*
we are using compass for yaw
*/
2021-07-30 01:41:09 -03:00
if ( compass . last_update_usec ( ) ! = _compass_last_update ) {
yaw_deltat = ( compass . last_update_usec ( ) - _compass_last_update ) * 1.0e-6 f ;
_compass_last_update = compass . last_update_usec ( ) ;
2012-08-21 23:19:51 -03:00
// we force an additional compass read()
// here. This has the effect of throwing away
// the first compass value, which can be bad
2021-08-11 21:15:00 -03:00
if ( ! have_initial_yaw & & compass . read ( ) ) {
2021-07-30 01:41:09 -03:00
const float heading = compass . calculate_heading ( _dcm_matrix ) ;
2012-08-21 23:19:51 -03:00
_dcm_matrix . from_euler ( roll , pitch , heading ) ;
_omega_yaw_P . zero ( ) ;
2021-08-11 21:15:00 -03:00
have_initial_yaw = true ;
2012-08-21 23:19:51 -03:00
}
new_value = true ;
2021-07-30 01:41:09 -03:00
yaw_error = yaw_error_compass ( compass ) ;
2013-11-03 22:57:06 -04:00
// also update the _gps_last_update, so if we later
// disable the compass due to significant yaw error we
// don't suddenly change yaw with a reset
2014-03-30 08:00:25 -03:00
_gps_last_update = _gps . last_fix_time_ms ( ) ;
2012-08-21 23:19:51 -03:00
}
2021-08-11 09:11:54 -03:00
} else if ( AP : : ahrs ( ) . get_fly_forward ( ) & & have_gps ( ) ) {
2013-06-24 23:43:53 -03:00
/*
we are using GPS for yaw
*/
2014-03-30 08:00:25 -03:00
if ( _gps . last_fix_time_ms ( ) ! = _gps_last_update & &
2015-09-23 04:29:43 -03:00
_gps . ground_speed ( ) > = GPS_SPEED_MIN ) {
2014-03-30 08:00:25 -03:00
yaw_deltat = ( _gps . last_fix_time_ms ( ) - _gps_last_update ) * 1.0e-3 f ;
_gps_last_update = _gps . last_fix_time_ms ( ) ;
2013-06-24 23:43:53 -03:00
new_value = true ;
2021-01-21 18:19:38 -04:00
const float gps_course_rad = ToRad ( _gps . ground_course ( ) ) ;
2017-12-03 06:10:19 -04:00
const float yaw_error_rad = wrap_PI ( gps_course_rad - yaw ) ;
2013-06-24 23:43:53 -03:00
yaw_error = sinf ( yaw_error_rad ) ;
/* reset yaw to match GPS heading under any of the
following 3 conditions :
1 ) if we have reached GPS_SPEED_MIN and have never had
yaw information before
2 ) if the last time we got yaw information from the GPS
is more than 20 seconds ago , which means we may have
suffered from considerable gyro drift
3 ) if we are over 3 * GPS_SPEED_MIN ( which means 9 m / s )
and our yaw error is over 60 degrees , which means very
poor yaw . This can happen on bungee launch when the
operator pulls back the plane rapidly enough then on
release the GPS heading changes very rapidly
*/
2021-08-11 21:15:00 -03:00
if ( ! have_initial_yaw | |
2015-09-23 04:29:43 -03:00
yaw_deltat > 20 | |
( _gps . ground_speed ( ) > = 3 * GPS_SPEED_MIN & & fabsf ( yaw_error_rad ) > = 1.047f ) ) {
2013-06-24 23:43:53 -03:00
// reset DCM matrix based on current yaw
_dcm_matrix . from_euler ( roll , pitch , gps_course_rad ) ;
2012-08-21 23:19:51 -03:00
_omega_yaw_P . zero ( ) ;
2021-08-11 21:15:00 -03:00
have_initial_yaw = true ;
2013-06-24 23:43:53 -03:00
yaw_error = 0 ;
2012-08-21 23:19:51 -03:00
}
}
}
if ( ! new_value ) {
// we don't have any new yaw information
// slowly decay _omega_yaw_P to cope with loss
// of our yaw source
2013-01-10 14:42:24 -04:00
_omega_yaw_P * = 0.97f ;
2012-08-21 23:19:51 -03:00
return ;
}
// convert the error vector to body frame
2017-12-03 06:10:19 -04:00
const float error_z = _dcm_matrix . c . z * yaw_error ;
2012-08-21 23:19:51 -03:00
// the spin rate changes the P gain, and disables the
// integration at higher rates
2017-12-03 06:10:19 -04:00
const float spin_rate = _omega . length ( ) ;
2012-08-21 23:19:51 -03:00
2014-10-21 09:40:16 -03:00
// sanity check _kp_yaw
if ( _kp_yaw < AP_AHRS_YAW_P_MIN ) {
2022-07-05 00:08:56 -03:00
_kp_yaw . set ( AP_AHRS_YAW_P_MIN ) ;
2014-10-21 09:40:16 -03:00
}
2012-08-21 23:19:51 -03:00
// update the proportional control to drag the
// yaw back to the right value. We use a gain
// that depends on the spin rate. See the fastRotations.pdf
// paper from Bill Premerlani
2014-01-18 03:18:12 -04:00
// We also adjust the gain depending on the rate of change of horizontal velocity which
// is proportional to how observable the heading is from the acceerations and GPS velocity
// The accelration derived heading will be more reliable in turns than compass or GPS
2012-08-21 23:19:51 -03:00
2014-02-26 18:41:28 -04:00
_omega_yaw_P . z = error_z * _P_gain ( spin_rate ) * _kp_yaw * _yaw_gain ( ) ;
2015-04-27 21:26:36 -03:00
if ( use_fast_gains ( ) ) {
2012-08-21 23:19:51 -03:00
_omega_yaw_P . z * = 8 ;
}
// don't update the drift term if we lost the yaw reference
// for more than 2 seconds
2013-01-10 14:42:24 -04:00
if ( yaw_deltat < 2.0f & & spin_rate < ToRad ( SPIN_RATE_LIMIT ) ) {
2012-08-21 23:19:51 -03:00
// also add to the I term
2013-05-05 00:51:45 -03:00
_omega_I_sum . z + = error_z * _ki_yaw * yaw_deltat ;
2012-08-21 23:19:51 -03:00
}
2015-04-21 22:17:59 -03:00
_error_yaw = 0.8f * _error_yaw + 0.2f * fabsf ( yaw_error ) ;
2012-06-27 22:09:22 -03:00
}
2012-03-23 02:22:56 -03:00
2012-06-27 22:09:22 -03:00
2013-11-04 00:50:33 -04:00
/**
2014-02-26 18:41:28 -04:00
return an accel vector delayed by AHRS_ACCEL_DELAY samples for a
specific accelerometer instance
2013-11-04 00:50:33 -04:00
*/
2014-02-26 18:41:28 -04:00
Vector3f AP_AHRS_DCM : : ra_delayed ( uint8_t instance , const Vector3f & ra )
2013-11-04 00:50:33 -04:00
{
// get the old element, and then fill it with the new element
2017-12-03 06:10:19 -04:00
const Vector3f ret = _ra_delay_buffer [ instance ] ;
2014-02-26 18:41:28 -04:00
_ra_delay_buffer [ instance ] = ra ;
2014-05-15 09:19:54 -03:00
if ( ret . is_zero ( ) ) {
// use the current vector if the previous vector is exactly
// zero. This prevents an error on initialisation
return ra ;
}
2013-11-04 00:50:33 -04:00
return ret ;
}
2012-06-27 22:09:22 -03:00
2021-08-11 21:44:52 -03:00
/* returns true if attitude should be corrected from GPS-derived
* velocity - deltas . We turn this off for Copter and other similar
* vehicles while the vehicle is disarmed to avoid the HUD bobbing
* around while the vehicle is disarmed .
*/
bool AP_AHRS_DCM : : should_correct_centrifugal ( ) const
{
2021-10-25 14:08:59 -03:00
# if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduSub) || APM_BUILD_TYPE(APM_BUILD_Blimp)
2021-08-11 21:44:52 -03:00
return hal . util - > get_soft_armed ( ) ;
# endif
return true ;
}
2012-06-27 22:09:22 -03:00
// perform drift correction. This function aims to update _omega_P and
// _omega_I with our best estimate of the short term and long term
// gyro error. The _omega_P value is what pulls our attitude solution
// back towards the reference vector quickly. The _omega_I term is an
// attempt to learn the long term drift rate of the gyros.
//
// This drift correction implementation is based on a paper
// by Bill Premerlani from here:
// http://gentlenav.googlecode.com/files/RollPitchDriftCompensation.pdf
void
AP_AHRS_DCM : : drift_correction ( float deltat )
{
Vector3f velocity ;
uint32_t last_correction_time ;
// perform yaw drift correction if we have a new yaw reference
// vector
drift_correction_yaw ( ) ;
2018-03-10 05:35:03 -04:00
const AP_InertialSensor & _ins = AP : : ins ( ) ;
2012-12-12 03:22:56 -04:00
// rotate accelerometer values into the earth frame
2014-02-26 18:41:28 -04:00
for ( uint8_t i = 0 ; i < _ins . get_accel_count ( ) ; i + + ) {
2022-07-26 21:21:01 -03:00
if ( _ins . use_accel ( i ) ) {
2015-07-13 01:47:37 -03:00
/*
by using get_delta_velocity ( ) instead of get_accel ( ) the
accel value is sampled over the right time delta for
each sensor , which prevents an aliasing effect
*/
Vector3f delta_velocity ;
2021-02-11 17:34:36 -04:00
float delta_velocity_dt ;
_ins . get_delta_velocity ( i , delta_velocity , delta_velocity_dt ) ;
2015-08-05 02:20:09 -03:00
if ( delta_velocity_dt > 0 ) {
2022-07-26 21:21:01 -03:00
Vector3f accel_ef = _dcm_matrix * ( delta_velocity / delta_velocity_dt ) ;
2015-08-05 02:20:09 -03:00
// integrate the accel vector in the earth frame between GPS readings
2022-07-26 21:21:01 -03:00
_ra_sum [ i ] + = accel_ef * deltat ;
2015-08-05 02:20:09 -03:00
}
2014-02-26 18:41:28 -04:00
}
}
2012-06-27 22:09:22 -03:00
2022-07-26 04:50:35 -03:00
// set _accel_ef_blended based on filtered accel
2022-07-26 21:21:01 -03:00
_accel_ef = _dcm_matrix * _ins . get_accel ( ) ;
2014-10-31 20:19:11 -03:00
2012-06-27 22:09:22 -03:00
// keep a sum of the deltat values, so we know how much time
// we have integrated over
_ra_deltat + = deltat ;
2017-12-01 19:50:46 -04:00
const AP_GPS & _gps = AP : : gps ( ) ;
2021-08-11 09:11:54 -03:00
const bool fly_forward = AP : : ahrs ( ) . get_fly_forward ( ) ;
2017-12-01 19:50:46 -04:00
2015-09-23 04:29:43 -03:00
if ( ! have_gps ( ) | |
_gps . status ( ) < AP_GPS : : GPS_OK_FIX_3D | |
_gps . num_sats ( ) < _gps_minsats ) {
2012-11-05 05:06:44 -04:00
// no GPS, or not a good lock. From experience we need at
// least 6 satellites to get a really reliable velocity number
// from the GPS.
//
// As a fallback we use the fixed wing acceleration correction
// if we have an airspeed estimate (which we only have if
// _fly_forward is set), otherwise no correction
2013-01-10 14:42:24 -04:00
if ( _ra_deltat < 0.2f ) {
2012-06-27 22:09:22 -03:00
// not enough time has accumulated
return ;
}
2022-01-09 21:37:03 -04:00
float airspeed = _last_airspeed ;
# if AP_AIRSPEED_ENABLED
2015-01-19 20:27:58 -04:00
if ( airspeed_sensor_enabled ( ) ) {
2020-07-27 00:28:20 -03:00
airspeed = AP : : airspeed ( ) - > get_airspeed ( ) ;
2012-08-21 23:19:51 -03:00
}
2022-01-09 21:37:03 -04:00
# endif
2012-08-21 23:19:51 -03:00
// use airspeed to estimate our ground velocity in
// earth frame by subtracting the wind
velocity = _dcm_matrix . colx ( ) * airspeed ;
// add in wind estimate
velocity + = _wind ;
2015-11-19 23:06:21 -04:00
last_correction_time = AP_HAL : : millis ( ) ;
2012-08-21 23:19:51 -03:00
_have_gps_lock = false ;
2012-06-27 22:09:22 -03:00
} else {
2014-03-30 08:00:25 -03:00
if ( _gps . last_fix_time_ms ( ) = = _ra_sum_start ) {
2012-06-27 22:09:22 -03:00
// we don't have a new GPS fix - nothing more to do
return ;
}
2014-03-30 08:00:25 -03:00
velocity = _gps . velocity ( ) ;
last_correction_time = _gps . last_fix_time_ms ( ) ;
2012-08-21 23:19:51 -03:00
if ( _have_gps_lock = = false ) {
// if we didn't have GPS lock in the last drift
// correction interval then set the velocities equal
_last_velocity = velocity ;
}
_have_gps_lock = true ;
2013-05-06 21:52:14 -03:00
// keep last airspeed estimate for dead-reckoning purposes
Vector3f airspeed = velocity - _wind ;
2018-09-13 21:49:00 -03:00
// rotate vector to body frame
2021-08-18 07:20:46 -03:00
airspeed = _body_dcm_matrix . mul_transpose ( airspeed ) ;
2018-09-13 21:49:00 -03:00
// take positive component in X direction. This mimics a pitot
// tube
_last_airspeed = MAX ( airspeed . x , 0 ) ;
2013-05-06 21:52:14 -03:00
}
if ( have_gps ( ) ) {
// use GPS for positioning with any fix, even a 2D fix
2014-03-30 08:00:25 -03:00
_last_lat = _gps . location ( ) . lat ;
_last_lng = _gps . location ( ) . lng ;
2021-08-14 00:03:42 -03:00
_last_pos_ms = AP_HAL : : millis ( ) ;
2012-08-21 23:19:51 -03:00
_position_offset_north = 0 ;
_position_offset_east = 0 ;
2013-05-06 21:52:14 -03:00
// once we have a single GPS lock, we can update using
2012-08-21 23:19:51 -03:00
// dead-reckoning from then on
_have_position = true ;
2013-05-06 21:52:14 -03:00
} else {
// update dead-reckoning position estimate
_position_offset_north + = velocity . x * _ra_deltat ;
2015-09-23 04:29:43 -03:00
_position_offset_east + = velocity . y * _ra_deltat ;
2012-06-27 22:09:22 -03:00
}
// see if this is our first time through - in which case we
// just setup the start times and return
if ( _ra_sum_start = = 0 ) {
_ra_sum_start = last_correction_time ;
_last_velocity = velocity ;
return ;
}
2012-07-04 03:53:40 -03:00
// equation 9: get the corrected acceleration vector in earth frame. Units
2012-06-27 22:09:22 -03:00
// are m/s/s
2017-12-02 09:02:37 -04:00
Vector3f GA_e ( 0.0f , 0.0f , - 1.0f ) ;
2013-05-06 01:31:49 -03:00
2015-09-24 03:49:22 -03:00
if ( _ra_deltat < = 0 ) {
// waiting for more data
return ;
}
2013-11-04 00:50:33 -04:00
bool using_gps_corrections = false ;
2014-02-26 18:41:28 -04:00
float ra_scale = 1.0f / ( _ra_deltat * GRAVITY_MSS ) ;
2021-08-11 21:44:52 -03:00
if ( should_correct_centrifugal ( ) & & ( _have_gps_lock | | fly_forward ) ) {
2017-12-03 06:10:19 -04:00
const float v_scale = gps_gain . get ( ) * ra_scale ;
const Vector3f vdelta = ( velocity - _last_velocity ) * v_scale ;
2013-05-04 23:47:49 -03:00
GA_e + = vdelta ;
GA_e . normalize ( ) ;
if ( GA_e . is_inf ( ) ) {
// wait for some non-zero acceleration information
2015-11-19 23:06:21 -04:00
_last_failure_ms = AP_HAL : : millis ( ) ;
2013-05-04 23:47:49 -03:00
return ;
}
2013-11-04 00:50:33 -04:00
using_gps_corrections = true ;
2012-06-27 22:09:22 -03:00
}
2012-07-04 03:53:40 -03:00
// calculate the error term in earth frame.
2014-02-26 18:41:28 -04:00
// we do this for each available accelerometer then pick the
// accelerometer that leads to the smallest error term. This takes
// advantage of the different sample rates on different
// accelerometers to dramatically reduce the impact of aliasing
// due to harmonics of vibrations that match closely the sampling
// rate of our accelerometers. On the Pixhawk we have the LSM303D
// running at 800Hz and the MPU6000 running at 1kHz, by combining
// the two the effects of aliasing are greatly reduced.
Vector3f error [ INS_MAX_INSTANCES ] ;
2015-04-21 22:15:48 -03:00
float error_dirn [ INS_MAX_INSTANCES ] ;
2014-02-26 18:41:28 -04:00
Vector3f GA_b [ INS_MAX_INSTANCES ] ;
int8_t besti = - 1 ;
float best_error = 0 ;
for ( uint8_t i = 0 ; i < _ins . get_accel_count ( ) ; i + + ) {
2014-05-15 09:18:56 -03:00
if ( ! _ins . get_accel_health ( i ) ) {
2014-02-26 18:41:28 -04:00
// only use healthy sensors
continue ;
}
_ra_sum [ i ] * = ra_scale ;
2013-11-04 00:50:33 -04:00
2014-02-26 18:41:28 -04:00
// get the delayed ra_sum to match the GPS lag
if ( using_gps_corrections ) {
GA_b [ i ] = ra_delayed ( i , _ra_sum [ i ] ) ;
} else {
GA_b [ i ] = _ra_sum [ i ] ;
}
2014-04-21 02:23:01 -03:00
if ( GA_b [ i ] . is_zero ( ) ) {
// wait for some non-zero acceleration information
continue ;
}
2014-02-26 18:41:28 -04:00
GA_b [ i ] . normalize ( ) ;
if ( GA_b [ i ] . is_inf ( ) ) {
// wait for some non-zero acceleration information
continue ;
}
error [ i ] = GA_b [ i ] % GA_e ;
2015-04-21 22:15:48 -03:00
// Take dot product to catch case vectors are opposite sign and parallel
error_dirn [ i ] = GA_b [ i ] * GA_e ;
2017-12-03 06:10:19 -04:00
const float error_length = error [ i ] . length ( ) ;
2014-02-26 18:41:28 -04:00
if ( besti = = - 1 | | error_length < best_error ) {
besti = i ;
best_error = error_length ;
}
2015-04-21 22:15:48 -03:00
// Catch case where orientation is 180 degrees out
if ( error_dirn [ besti ] < 0.0f ) {
best_error = 1.0f ;
}
2013-11-04 00:50:33 -04:00
}
2014-02-26 18:41:28 -04:00
if ( besti = = - 1 ) {
// no healthy accelerometers!
2015-11-19 23:06:21 -04:00
_last_failure_ms = AP_HAL : : millis ( ) ;
2013-11-03 22:59:38 -04:00
return ;
2012-07-06 00:03:46 -03:00
}
2013-11-03 22:59:38 -04:00
2014-02-26 18:41:28 -04:00
_active_accel_instance = besti ;
2012-07-06 00:03:46 -03:00
# define YAW_INDEPENDENT_DRIFT_CORRECTION 0
2012-08-21 23:19:51 -03:00
# if YAW_INDEPENDENT_DRIFT_CORRECTION
2012-07-04 03:53:40 -03:00
// step 2 calculate earth_error_Z
2017-12-03 06:10:19 -04:00
const float earth_error_Z = error . z ;
2012-07-04 03:53:40 -03:00
// equation 10
2021-09-11 07:29:48 -03:00
const float tilt = GA_e . xy ( ) . length ( ) ;
2012-07-04 03:53:40 -03:00
// equation 11
2017-12-03 06:10:19 -04:00
const float theta = atan2f ( GA_b [ besti ] . y , GA_b [ besti ] . x ) ;
2012-08-21 23:19:51 -03:00
2012-07-04 03:53:40 -03:00
// equation 12
2017-12-03 06:10:19 -04:00
const Vector3f GA_e2 = Vector3f ( cosf ( theta ) * tilt , sinf ( theta ) * tilt , GA_e . z ) ;
2012-07-04 03:53:40 -03:00
// step 6
2014-02-26 18:41:28 -04:00
error = GA_b [ besti ] % GA_e2 ;
2012-07-06 00:03:46 -03:00
error . z = earth_error_Z ;
# endif // YAW_INDEPENDENT_DRIFT_CORRECTION
2012-07-04 19:11:37 -03:00
2012-07-19 22:49:40 -03:00
// to reduce the impact of two competing yaw controllers, we
// reduce the impact of the gps/accelerometers on yaw when we are
// flat, but still allow for yaw correction using the
2012-07-20 03:23:56 -03:00
// accelerometers at high roll angles as long as we have a GPS
2014-10-14 20:12:50 -03:00
if ( AP_AHRS_DCM : : use_compass ( ) ) {
2016-04-16 06:59:20 -03:00
if ( have_gps ( ) & & is_equal ( gps_gain . get ( ) , 1.0f ) ) {
2014-02-26 18:41:28 -04:00
error [ besti ] . z * = sinf ( fabsf ( roll ) ) ;
2012-08-21 23:19:51 -03:00
} else {
2014-02-26 18:41:28 -04:00
error [ besti ] . z = 0 ;
2012-08-21 23:19:51 -03:00
}
2012-07-04 19:11:37 -03:00
}
2012-06-27 22:09:22 -03:00
2013-11-06 22:54:16 -04:00
// if ins is unhealthy then stop attitude drift correction and
// hope the gyros are OK for a while. Just slowly reduce _omega_P
// to prevent previous bad accels from throwing us off
if ( ! _ins . healthy ( ) ) {
2014-02-26 18:41:28 -04:00
error [ besti ] . zero ( ) ;
2013-11-06 22:54:16 -04:00
} else {
// convert the error term to body frame
2014-02-26 18:41:28 -04:00
error [ besti ] = _dcm_matrix . mul_transpose ( error [ besti ] ) ;
2013-11-06 22:54:16 -04:00
}
2012-06-27 22:09:22 -03:00
2014-02-26 18:41:28 -04:00
if ( error [ besti ] . is_nan ( ) | | error [ besti ] . is_inf ( ) ) {
2012-08-21 23:19:51 -03:00
// don't allow bad values
check_matrix ( ) ;
2015-11-19 23:06:21 -04:00
_last_failure_ms = AP_HAL : : millis ( ) ;
2012-08-21 23:19:51 -03:00
return ;
2012-08-18 00:53:59 -03:00
}
2015-04-21 22:17:59 -03:00
_error_rp = 0.8f * _error_rp + 0.2f * best_error ;
2012-07-04 03:53:40 -03:00
2012-06-27 22:09:22 -03:00
// base the P gain on the spin rate
2017-12-03 06:10:19 -04:00
const float spin_rate = _omega . length ( ) ;
2012-06-27 22:09:22 -03:00
2014-10-21 09:40:16 -03:00
// sanity check _kp value
if ( _kp < AP_AHRS_RP_P_MIN ) {
2022-07-05 00:08:56 -03:00
_kp . set ( AP_AHRS_RP_P_MIN ) ;
2014-10-21 09:40:16 -03:00
}
2012-06-27 22:09:22 -03:00
// we now want to calculate _omega_P and _omega_I. The
// _omega_P value is what drags us quickly to the
// accelerometer reading.
2014-02-26 18:41:28 -04:00
_omega_P = error [ besti ] * _P_gain ( spin_rate ) * _kp ;
2015-04-27 21:26:36 -03:00
if ( use_fast_gains ( ) ) {
2012-08-21 23:19:51 -03:00
_omega_P * = 8 ;
2012-08-21 02:38:06 -03:00
}
2012-06-27 22:09:22 -03:00
2021-08-11 09:11:54 -03:00
if ( fly_forward & & _gps . status ( ) > = AP_GPS : : GPS_OK_FIX_2D & &
2015-09-23 04:29:43 -03:00
_gps . ground_speed ( ) < GPS_SPEED_MIN & &
_ins . get_accel ( ) . x > = 7 & &
2021-08-18 07:20:46 -03:00
pitch > radians ( - 30 ) & & pitch < radians ( 30 ) ) {
2015-09-23 04:29:43 -03:00
// assume we are in a launch acceleration, and reduce the
// rp gain by 50% to reduce the impact of GPS lag on
// takeoff attitude when using a catapult
_omega_P * = 0.5f ;
2013-04-27 19:03:36 -03:00
}
2012-06-27 22:09:22 -03:00
// accumulate some integrator error
if ( spin_rate < ToRad ( SPIN_RATE_LIMIT ) ) {
2014-02-26 18:41:28 -04:00
_omega_I_sum + = error [ besti ] * _ki * _ra_deltat ;
2012-08-21 23:19:51 -03:00
_omega_I_sum_time + = _ra_deltat ;
2012-06-27 22:09:22 -03:00
}
if ( _omega_I_sum_time > = 5 ) {
2012-08-21 23:19:51 -03:00
// limit the rate of change of omega_I to the hardware
// reported maximum gyro drift rate. This ensures that
// short term errors don't cause a buildup of omega_I
// beyond the physical limits of the device
2021-07-20 00:40:57 -03:00
const float change_limit = AP : : ins ( ) . get_gyro_drift_rate ( ) * _omega_I_sum_time ;
2013-05-01 21:25:40 -03:00
_omega_I_sum . x = constrain_float ( _omega_I_sum . x , - change_limit , change_limit ) ;
_omega_I_sum . y = constrain_float ( _omega_I_sum . y , - change_limit , change_limit ) ;
_omega_I_sum . z = constrain_float ( _omega_I_sum . z , - change_limit , change_limit ) ;
2012-08-21 23:19:51 -03:00
_omega_I + = _omega_I_sum ;
_omega_I_sum . zero ( ) ;
_omega_I_sum_time = 0 ;
2012-06-27 22:09:22 -03:00
}
// zero our accumulator ready for the next GPS step
2018-10-30 14:16:50 -03:00
memset ( ( void * ) & _ra_sum [ 0 ] , 0 , sizeof ( _ra_sum ) ) ;
2012-06-27 22:09:22 -03:00
_ra_deltat = 0 ;
_ra_sum_start = last_correction_time ;
// remember the velocity for next time
_last_velocity = velocity ;
2012-03-23 02:22:56 -03:00
}
2010-10-24 15:37:10 -03:00
2012-08-11 02:55:53 -03:00
// update our wind speed estimate
2014-02-08 02:31:05 -04:00
void AP_AHRS_DCM : : estimate_wind ( void )
2012-08-11 02:55:53 -03:00
{
2021-08-16 23:34:15 -03:00
if ( ! AP : : ahrs ( ) . get_wind_estimation_enabled ( ) ) {
2013-05-23 22:21:23 -03:00
return ;
}
2014-02-08 02:31:05 -04:00
const Vector3f & velocity = _last_velocity ;
2013-05-23 22:21:23 -03:00
2012-08-21 23:19:51 -03:00
// this is based on the wind speed estimation code from MatrixPilot by
// Bill Premerlani. Adaption for ArduPilot by Jon Challinger
// See http://gentlenav.googlecode.com/files/WindEstimation.pdf
2017-12-03 06:10:19 -04:00
const Vector3f fuselageDirection = _dcm_matrix . colx ( ) ;
const Vector3f fuselageDirectionDiff = fuselageDirection - _last_fuse ;
const uint32_t now = AP_HAL : : millis ( ) ;
2012-08-21 23:19:51 -03:00
// scrap our data and start over if we're taking too long to get a direction change
if ( now - _last_wind_time > 10000 ) {
_last_wind_time = now ;
_last_fuse = fuselageDirection ;
_last_vel = velocity ;
return ;
}
float diff_length = fuselageDirectionDiff . length ( ) ;
2013-01-10 14:42:24 -04:00
if ( diff_length > 0.2f ) {
2012-08-21 23:19:51 -03:00
// when turning, use the attitude response to estimate
// wind speed
float V ;
2017-12-03 06:10:19 -04:00
const Vector3f velocityDiff = velocity - _last_vel ;
2012-08-21 23:19:51 -03:00
// estimate airspeed it using equation 6
V = velocityDiff . length ( ) / diff_length ;
2017-12-03 06:10:19 -04:00
const Vector3f fuselageDirectionSum = fuselageDirection + _last_fuse ;
const Vector3f velocitySum = velocity + _last_vel ;
2012-08-21 23:19:51 -03:00
2015-09-16 14:30:13 -03:00
_last_fuse = fuselageDirection ;
_last_vel = velocity ;
2017-12-03 06:10:19 -04:00
const float theta = atan2f ( velocityDiff . y , velocityDiff . x ) - atan2f ( fuselageDirectionDiff . y , fuselageDirectionDiff . x ) ;
const float sintheta = sinf ( theta ) ;
const float costheta = cosf ( theta ) ;
2012-08-21 23:19:51 -03:00
Vector3f wind = Vector3f ( ) ;
wind . x = velocitySum . x - V * ( costheta * fuselageDirectionSum . x - sintheta * fuselageDirectionSum . y ) ;
wind . y = velocitySum . y - V * ( sintheta * fuselageDirectionSum . x + costheta * fuselageDirectionSum . y ) ;
wind . z = velocitySum . z - V * fuselageDirectionSum . z ;
2013-01-10 14:42:24 -04:00
wind * = 0.5f ;
2012-08-21 23:19:51 -03:00
2013-04-22 19:57:33 -03:00
if ( wind . length ( ) < _wind . length ( ) + 20 ) {
_wind = _wind * 0.95f + wind * 0.05f ;
}
2012-08-21 23:19:51 -03:00
_last_wind_time = now ;
2022-01-09 21:37:03 -04:00
return ;
}
# if AP_AIRSPEED_ENABLED
if ( now - _last_wind_time > 2000 & & airspeed_sensor_enabled ( ) ) {
2012-08-21 23:19:51 -03:00
// when flying straight use airspeed to get wind estimate if available
2020-07-27 00:28:20 -03:00
const Vector3f airspeed = _dcm_matrix . colx ( ) * AP : : airspeed ( ) - > get_airspeed ( ) ;
2017-12-03 06:10:19 -04:00
const Vector3f wind = velocity - ( airspeed * get_EAS2TAS ( ) ) ;
2013-01-10 14:42:24 -04:00
_wind = _wind * 0.92f + wind * 0.08f ;
2015-09-23 04:29:43 -03:00
}
2022-01-09 21:37:03 -04:00
# endif
2012-08-11 02:55:53 -03:00
}
2012-08-21 23:19:51 -03:00
// return our current position estimate using
2012-08-10 23:00:31 -03:00
// dead-reckoning or GPS
2023-02-02 18:58:38 -04:00
bool AP_AHRS_DCM : : get_location ( Location & loc ) const
2012-08-10 23:00:31 -03:00
{
2013-08-04 21:16:31 -03:00
loc . lat = _last_lat ;
loc . lng = _last_lng ;
2021-01-18 01:32:37 -04:00
const auto & baro = AP : : baro ( ) ;
const auto & gps = AP : : gps ( ) ;
if ( _gps_use = = GPSUse : : EnableWithHeight & &
gps . status ( ) > = AP_GPS : : GPS_OK_FIX_3D ) {
loc . alt = gps . location ( ) . alt ;
} else {
2021-07-24 20:08:28 -03:00
loc . alt = baro . get_altitude ( ) * 100 + AP : : ahrs ( ) . get_home ( ) . alt ;
2021-01-18 01:32:37 -04:00
}
2019-01-01 19:58:24 -04:00
loc . relative_alt = 0 ;
loc . terrain_alt = 0 ;
2019-02-24 20:13:21 -04:00
loc . offset ( _position_offset_north , _position_offset_east ) ;
2021-08-14 00:03:42 -03:00
if ( _have_position ) {
const uint32_t now = AP_HAL : : millis ( ) ;
float dt = 0 ;
gps . get_lag ( dt ) ;
dt + = constrain_float ( ( now - _last_pos_ms ) * 0.001 , 0 , 0.5 ) ;
Vector2f dpos = _last_velocity . xy ( ) * dt ;
loc . offset ( dpos . x , dpos . y ) ;
2014-01-02 07:06:10 -04:00
}
2014-02-14 18:23:41 -04:00
return _have_position ;
2012-08-10 23:00:31 -03:00
}
2020-01-06 20:45:58 -04:00
bool AP_AHRS_DCM : : airspeed_estimate ( float & airspeed_ret ) const
2012-08-24 08:22:58 -03:00
{
2022-01-09 21:37:03 -04:00
# if AP_AIRSPEED_ENABLED
2020-07-27 00:28:20 -03:00
const auto * airspeed = AP : : airspeed ( ) ;
2022-01-09 21:37:03 -04:00
if ( airspeed ! = nullptr ) {
return airspeed_estimate ( airspeed - > get_primary ( ) , airspeed_ret ) ;
2020-07-27 00:28:20 -03:00
}
2022-01-09 21:37:03 -04:00
# endif
// airspeed_estimate will also make this nullptr check and act
// appropriately when we call it with a dummy sensor ID.
return airspeed_estimate ( 0 , airspeed_ret ) ;
2020-08-18 12:08:35 -03:00
}
2020-07-27 00:28:20 -03:00
// return an airspeed estimate:
// - from a real sensor if available
// - otherwise from a GPS-derived wind-triangle estimate (if GPS available)
// - otherwise from a cached wind-triangle estimate value (but returning false)
2020-08-18 12:08:35 -03:00
bool AP_AHRS_DCM : : airspeed_estimate ( uint8_t airspeed_index , float & airspeed_ret ) const
{
2022-01-09 21:37:03 -04:00
// airspeed_ret: will always be filled-in by get_unconstrained_airspeed_estimate which fills in airspeed_ret in this order:
// airspeed as filled-in by an enabled airsped sensor
// if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation
// Or if none of the above, fills-in using the previous airspeed estimate
// Return false: if we are using the previous airspeed estimate
if ( ! get_unconstrained_airspeed_estimate ( airspeed_index , airspeed_ret ) ) {
2020-08-18 12:08:35 -03:00
return false ;
}
2021-08-19 23:20:59 -03:00
const float _wind_max = AP : : ahrs ( ) . get_max_wind ( ) ;
2020-08-18 12:08:35 -03:00
if ( _wind_max > 0 & & AP : : gps ( ) . status ( ) > = AP_GPS : : GPS_OK_FIX_2D ) {
2015-09-23 04:29:43 -03:00
// constrain the airspeed by the ground speed
// and AHRS_WIND_MAX
2017-12-01 19:50:46 -04:00
const float gnd_speed = AP : : gps ( ) . ground_speed ( ) ;
2020-01-06 20:45:58 -04:00
float true_airspeed = airspeed_ret * get_EAS2TAS ( ) ;
2015-09-23 04:29:43 -03:00
true_airspeed = constrain_float ( true_airspeed ,
gnd_speed - _wind_max ,
2013-07-10 01:02:14 -03:00
gnd_speed + _wind_max ) ;
2020-01-06 20:45:58 -04:00
airspeed_ret = true_airspeed / get_EAS2TAS ( ) ;
2015-09-23 04:29:43 -03:00
}
2020-07-27 00:54:21 -03:00
return true ;
2012-08-24 08:22:58 -03:00
}
2014-01-02 07:06:10 -04:00
2022-01-09 21:37:03 -04:00
// airspeed_ret: will always be filled-in by get_unconstrained_airspeed_estimate which fills in airspeed_ret in this order:
// airspeed as filled-in by an enabled airsped sensor
// if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation
// Or if none of the above, fills-in using the previous airspeed estimate
// Return false: if we are using the previous airspeed estimate
bool AP_AHRS_DCM : : get_unconstrained_airspeed_estimate ( uint8_t airspeed_index , float & airspeed_ret ) const
{
# if AP_AIRSPEED_ENABLED
if ( airspeed_sensor_enabled ( airspeed_index ) ) {
airspeed_ret = AP : : airspeed ( ) - > get_airspeed ( airspeed_index ) ;
return true ;
}
# endif
if ( AP : : ahrs ( ) . get_wind_estimation_enabled ( ) & & have_gps ( ) ) {
// estimated via GPS speed and wind
airspeed_ret = _last_airspeed ;
return true ;
}
// Else give the last estimate, but return false.
// This is used by the dead-reckoning code
airspeed_ret = _last_airspeed ;
return false ;
}
2021-07-24 20:08:28 -03:00
bool AP_AHRS : : set_home ( const Location & loc )
2014-01-02 07:06:10 -04:00
{
2021-06-22 09:26:20 -03:00
WITH_SEMAPHORE ( _rsem ) ;
2019-02-12 22:46:36 -04:00
// check location is valid
if ( loc . lat = = 0 & & loc . lng = = 0 & & loc . alt = = 0 ) {
return false ;
}
2019-04-08 10:51:22 -03:00
if ( ! loc . check_latlng ( ) ) {
2019-02-12 22:46:36 -04:00
return false ;
}
2019-02-20 17:39:37 -04:00
// home must always be global frame at the moment as .alt is
// accessed directly by the vehicles and they may not be rigorous
// in checking the frame type.
Location tmp = loc ;
2019-03-14 22:45:32 -03:00
if ( ! tmp . change_alt_frame ( Location : : AltFrame : : ABSOLUTE ) ) {
2019-02-20 17:39:37 -04:00
return false ;
}
2019-02-12 22:46:36 -04:00
2022-01-30 01:48:06 -04:00
# if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
if ( ! _home_is_set ) {
// record home is set
AP : : logger ( ) . Write_Event ( LogEvent : : SET_HOME ) ;
}
# endif
2019-02-20 17:39:37 -04:00
_home = tmp ;
2018-05-23 03:58:46 -03:00
_home_is_set = true ;
2018-10-10 00:27:00 -03:00
Log_Write_Home_And_Origin ( ) ;
// send new home and ekf origin to GCS
2019-02-24 21:44:19 -04:00
gcs ( ) . send_message ( MSG_HOME ) ;
gcs ( ) . send_message ( MSG_ORIGIN ) ;
2018-05-29 20:47:10 -03:00
2019-05-09 04:49:55 -03:00
AP_HAL : : Util : : PersistentData & pd = hal . util - > persistent_data ;
pd . home_lat = loc . lat ;
pd . home_lon = loc . lng ;
pd . home_alt_cm = loc . alt ;
2019-04-20 07:02:46 -03:00
2018-05-29 20:47:10 -03:00
return true ;
2014-01-02 07:06:10 -04:00
}
2014-01-03 20:15:34 -04:00
2014-05-15 04:09:18 -03:00
/*
check if the AHRS subsystem is healthy
*/
2015-01-31 22:31:24 -04:00
bool AP_AHRS_DCM : : healthy ( void ) const
2014-05-15 04:09:18 -03:00
{
// consider ourselves healthy if there have been no failures for 5 seconds
2015-11-19 23:06:21 -04:00
return ( _last_failure_ms = = 0 | | AP_HAL : : millis ( ) - _last_failure_ms > 5000 ) ;
2014-05-15 04:09:18 -03:00
}
2019-03-13 23:51:57 -03:00
/*
return NED velocity if we have GPS lock
*/
bool AP_AHRS_DCM : : get_velocity_NED ( Vector3f & vec ) const
{
const AP_GPS & _gps = AP : : gps ( ) ;
if ( _gps . status ( ) < AP_GPS : : GPS_OK_FIX_3D ) {
return false ;
}
vec = _gps . velocity ( ) ;
return true ;
}
2021-08-18 07:20:46 -03:00
// Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.
// This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for.
2023-05-31 04:24:15 -03:00
bool AP_AHRS_DCM : : get_vert_pos_rate_D ( float & velocity ) const
2021-08-18 07:20:46 -03:00
{
Vector3f velned ;
if ( ! get_velocity_NED ( velned ) ) {
return false ;
}
velocity = velned . z ;
return true ;
}
2020-08-11 02:02:55 -03:00
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
2021-01-20 23:42:19 -04:00
// requires_position should be true if horizontal position configuration should be checked (not used)
bool AP_AHRS_DCM : : pre_arm_check ( bool requires_position , char * failure_msg , uint8_t failure_msg_len ) const
2020-08-11 02:02:55 -03:00
{
if ( ! healthy ( ) ) {
hal . util - > snprintf ( failure_msg , failure_msg_len , " Not healthy " ) ;
return false ;
}
return true ;
}
2021-08-14 00:03:42 -03:00
/*
relative - origin functions for fallback in AP_InertialNav
*/
2021-08-18 07:20:46 -03:00
bool AP_AHRS_DCM : : get_origin ( Location & ret ) const
2021-08-14 00:03:42 -03:00
{
ret = last_origin ;
if ( ret . is_zero ( ) ) {
// use home if we never have had an origin
ret = AP : : ahrs ( ) . get_home ( ) ;
}
return ! ret . is_zero ( ) ;
}
bool AP_AHRS_DCM : : get_relative_position_NED_origin ( Vector3f & posNED ) const
{
Location origin ;
2021-08-18 07:20:46 -03:00
if ( ! AP_AHRS_DCM : : get_origin ( origin ) ) {
2021-08-14 00:03:42 -03:00
return false ;
}
Location loc ;
2022-01-20 19:42:40 -04:00
if ( ! AP_AHRS_DCM : : get_location ( loc ) ) {
2021-08-14 00:03:42 -03:00
return false ;
}
posNED = origin . get_distance_NED ( loc ) ;
return true ;
}
bool AP_AHRS_DCM : : get_relative_position_NE_origin ( Vector2f & posNE ) const
{
Vector3f posNED ;
if ( ! AP_AHRS_DCM : : get_relative_position_NED_origin ( posNED ) ) {
return false ;
}
posNE = posNED . xy ( ) ;
return true ;
}
bool AP_AHRS_DCM : : get_relative_position_D_origin ( float & posD ) const
{
Vector3f posNED ;
if ( ! AP_AHRS_DCM : : get_relative_position_NED_origin ( posNED ) ) {
return false ;
}
posD = posNED . z ;
return true ;
}
2021-08-18 07:20:46 -03:00
2022-07-08 01:15:35 -03:00
void AP_AHRS_DCM : : send_ekf_status_report ( GCS_MAVLINK & link ) const
2021-08-18 07:20:46 -03:00
{
}
2022-12-17 17:06:45 -04:00
// return true if DCM has a yaw source available
bool AP_AHRS_DCM : : yaw_source_available ( void ) const
{
return AP : : compass ( ) . use_for_yaw ( ) ;
}
2023-01-03 06:19:00 -04:00
void AP_AHRS_DCM : : get_control_limits ( float & ekfGndSpdLimit , float & ekfNavVelGainScaler ) const
{
// lower gains in VTOL controllers when flying on DCM
ekfGndSpdLimit = 50.0 ;
ekfNavVelGainScaler = 0.5 ;
}