2016-02-17 21:25:13 -04:00
# pragma once
2013-08-29 02:34:34 -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 .
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-03-11 04:59:53 -03:00
/*
2012-08-21 23:19:51 -03:00
* DCM based AHRS ( Attitude Heading Reference System ) interface for
* ArduPilot
*
*/
2012-03-11 04:59:53 -03:00
2023-09-20 08:20:44 -03:00
# include "AP_AHRS_config.h"
# if AP_AHRS_DCM_ENABLED
2021-07-21 03:37:37 -03:00
# include "AP_AHRS_Backend.h"
2021-07-20 10:04:20 -03:00
class AP_AHRS_DCM : public AP_AHRS_Backend {
2010-12-01 03:58:04 -04:00
public :
2021-08-18 07:20:46 -03:00
AP_AHRS_DCM ( AP_Float & kp_yaw ,
AP_Float & kp ,
AP_Float & _gps_gain ,
AP_Float & _beta ,
AP_Enum < GPSUse > & gps_use ,
AP_Int8 & gps_minsats )
: AP_AHRS_Backend ( ) ,
_kp_yaw ( kp_yaw ) ,
_kp ( kp ) ,
gps_gain ( _gps_gain ) ,
beta ( _beta ) ,
_gps_use ( gps_use ) ,
_gps_minsats ( gps_minsats )
2017-12-12 21:06:11 -04:00
{
_dcm_matrix . identity ( ) ;
}
2017-08-30 05:15:33 -03:00
/* Do not allow copies */
2022-09-30 06:50:43 -03:00
CLASS_NO_COPY ( AP_AHRS_DCM ) ;
2017-08-30 05:15:33 -03:00
2014-10-28 08:22:48 -03:00
// reset the current gyro drift estimate
// should be called if gyro offsets are recalculated
2017-02-23 06:27:21 -04:00
void reset_gyro_drift ( ) override ;
2014-10-28 08:22:48 -03:00
2012-08-21 23:19:51 -03:00
// Methods
2021-08-18 07:20:46 -03:00
void update ( ) override ;
void get_results ( Estimates & results ) override ;
void reset ( ) override { reset ( false ) ; }
2012-08-21 23:19:51 -03:00
2021-08-11 21:15:00 -03:00
// return true if yaw has been initialised
bool yaw_initialised ( void ) const {
return have_initial_yaw ;
}
2012-08-21 23:19:51 -03:00
// status reporting
2021-08-18 07:20:46 -03:00
float get_error_rp ( ) const {
2015-09-23 04:29:43 -03:00
return _error_rp ;
}
2021-08-18 07:20:46 -03:00
float get_error_yaw ( ) const {
2015-09-23 04:29:43 -03:00
return _error_yaw ;
}
2012-08-21 23:19:51 -03:00
// return a wind estimation vector, in m/s
2023-01-12 03:12:01 -04:00
bool wind_estimate ( Vector3f & wind ) const override {
wind = _wind ;
return true ;
2012-08-21 23:19:51 -03:00
}
2012-08-12 22:08:10 -03:00
2012-08-24 08:22:58 -03:00
// return an airspeed estimate if available. return true
// if we have an estimate
2020-01-06 20:45:58 -04:00
bool airspeed_estimate ( float & airspeed_ret ) const override ;
2012-08-24 08:22:58 -03:00
2020-08-18 12:08:35 -03:00
// return an airspeed estimate if available. return true
// if we have an estimate from a specific sensor index
2021-08-18 07:20:46 -03:00
bool airspeed_estimate ( uint8_t airspeed_index , float & airspeed_ret ) const override ;
2020-08-18 12:08:35 -03:00
2020-07-28 01:29:57 -03:00
// return a synthetic airspeed estimate (one derived from sensors
// other than an actual airspeed sensor), if available. return
// true if we have a synthetic airspeed. ret will not be modified
// on failure.
2023-01-03 06:19:00 -04:00
bool synthetic_airspeed ( float & ret ) const WARN_IF_UNUSED {
2020-07-28 01:29:57 -03:00
ret = _last_airspeed ;
return true ;
}
2021-08-19 23:44:05 -03:00
// return a ground vector estimate in meters/second, in North/East order
Vector2f groundspeed_vector ( ) override ;
2017-02-23 06:27:21 -04:00
bool use_compass ( ) override ;
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 get_quaternion ( Quaternion & quat ) const override WARN_IF_UNUSED ;
2014-02-08 04:11:12 -04:00
void estimate_wind ( void ) ;
2014-01-03 20:15:34 -04:00
2014-05-15 04:09:18 -03:00
// is the AHRS subsystem healthy?
2017-02-23 06:27:21 -04:00
bool healthy ( ) const override ;
2014-05-15 04:09:18 -03:00
2019-03-13 23:51:57 -03:00
bool get_velocity_NED ( Vector3f & vec ) const override ;
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 get_vert_pos_rate_D ( float & velocity ) const override ;
2021-08-18 07:20:46 -03:00
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 pre_arm_check ( bool requires_position , char * failure_msg , uint8_t failure_msg_len ) const override ;
2020-08-11 02:02:55 -03:00
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 get_origin ( Location & ret ) const override ;
2021-08-14 00:03:42 -03:00
bool get_relative_position_NED_origin ( Vector3f & vec ) const override ;
bool get_relative_position_NE_origin ( Vector2f & posNE ) const override ;
bool get_relative_position_D_origin ( float & posD ) const override ;
2021-08-19 23:52:20 -03:00
2022-07-08 01:15:35 -03:00
void send_ekf_status_report ( class GCS_MAVLINK & link ) const override ;
2021-08-18 07:20:46 -03:00
2022-12-17 17:06:45 -04:00
// return true if DCM has a yaw source
bool yaw_source_available ( void ) const ;
2023-01-03 06:19:00 -04:00
void get_control_limits ( float & ekfGndSpdLimit , float & controlScaleXY ) const override ;
2021-08-18 07:20:46 -03:00
private :
2021-08-19 23:52:20 -03:00
2023-09-17 23:40:41 -03:00
// dead-reckoning support
bool get_location ( Location & loc ) const ;
2021-08-19 23:52:20 -03:00
// settable parameters
2021-08-18 07:20:46 -03:00
AP_Float & _kp_yaw ;
AP_Float & _kp ;
AP_Float & gps_gain ;
2021-08-19 23:52:20 -03:00
2021-08-18 07:20:46 -03:00
AP_Float & beta ;
2021-08-19 23:52:20 -03:00
2021-08-18 07:20:46 -03:00
AP_Int8 & _gps_minsats ;
2021-08-19 23:52:20 -03:00
2021-08-18 07:20:46 -03:00
AP_Enum < GPSUse > & _gps_use ;
2021-07-20 01:21:09 -03:00
// these are experimentally derived from the simulator
// with large drift levels
static constexpr float _ki = 0.0087f ;
static constexpr float _ki_yaw = 0.01f ;
2012-08-21 23:19:51 -03:00
2021-08-18 07:20:46 -03:00
// accelerometer values in the earth frame in m/s/s
2022-07-26 21:21:01 -03:00
Vector3f _accel_ef ;
2021-08-18 07:20:46 -03:00
2012-08-21 23:19:51 -03:00
// Methods
2022-07-26 04:50:35 -03:00
void matrix_update ( void ) ;
2012-08-21 23:19:51 -03:00
void normalize ( void ) ;
void check_matrix ( void ) ;
bool renorm ( Vector3f const & a , Vector3f & result ) ;
void drift_correction ( float deltat ) ;
void drift_correction_yaw ( void ) ;
2021-07-30 01:41:09 -03:00
float yaw_error_compass ( class Compass & compass ) ;
2013-07-07 22:25:40 -03:00
bool have_gps ( void ) const ;
2015-04-27 21:26:36 -03:00
bool use_fast_gains ( void ) const ;
2019-04-21 00:08:29 -03:00
void backup_attitude ( void ) ;
2012-08-21 23:19:51 -03:00
2021-08-18 07:20:46 -03:00
// internal reset function. Called externally, we never reset the
// DCM matrix from the eulers. Called internally we may.
void reset ( bool recover_eulers ) ;
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:
2023-10-11 04:41:50 -03:00
// airspeed as filled-in by an enabled airspeed sensor
2022-01-09 21:37:03 -04:00
// 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 get_unconstrained_airspeed_estimate ( uint8_t airspeed_index , float & airspeed_ret ) const ;
2014-01-17 04:19:42 -04:00
// primary representation of attitude of board used for all inertial calculations
2012-08-21 23:19:51 -03:00
Matrix3f _dcm_matrix ;
2014-01-17 04:19:42 -04:00
// primary representation of attitude of flight vehicle body
Matrix3f _body_dcm_matrix ;
2021-08-18 07:20:46 -03:00
// euler angles - used for recovering if the DCM
// matrix becomes ill-conditioned and watchdog storage
float roll ;
float pitch ;
float yaw ;
2012-08-21 23:19:51 -03:00
Vector3f _omega_P ; // accel Omega proportional correction
Vector3f _omega_yaw_P ; // proportional yaw correction
Vector3f _omega_I ; // Omega Integrator correction
Vector3f _omega_I_sum ;
float _omega_I_sum_time ;
Vector3f _omega ; // Corrected Gyro_Vector data
2021-08-11 21:15:00 -03:00
bool have_initial_yaw ; // true if the yaw value has been initialised with a reference
2013-11-04 00:50:33 -04:00
// variables to cope with delaying the GA sum to match GPS lag
2014-02-26 18:41:28 -04:00
Vector3f ra_delayed ( uint8_t instance , const Vector3f & ra ) ;
Vector3f _ra_delay_buffer [ INS_MAX_INSTANCES ] ;
2013-11-04 00:50:33 -04:00
2012-08-21 23:19:51 -03:00
// P term gain based on spin rate
float _P_gain ( float spin_rate ) ;
2014-01-18 03:18:12 -04:00
// P term yaw gain based on rate of change of horiz velocity
2014-02-26 18:41:28 -04:00
float _yaw_gain ( void ) const ;
2014-01-18 03:18:12 -04: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 should_correct_centrifugal ( ) const ;
2012-08-21 23:19:51 -03:00
// state to support status reporting
float _renorm_val_sum ;
uint16_t _renorm_val_count ;
2021-07-20 01:21:09 -03:00
float _error_rp { 1.0f } ;
float _error_yaw { 1.0f } ;
2012-08-21 23:19:51 -03:00
2021-07-25 21:32:10 -03:00
// time in microseconds of last compass update
uint32_t _compass_last_update ;
2012-08-21 23:19:51 -03:00
// time in millis when we last got a GPS heading
uint32_t _gps_last_update ;
// state of accel drift correction
2014-02-26 18:41:28 -04:00
Vector3f _ra_sum [ INS_MAX_INSTANCES ] ;
2012-08-21 23:19:51 -03:00
Vector3f _last_velocity ;
float _ra_deltat ;
uint32_t _ra_sum_start ;
2021-08-19 23:57:54 -03:00
// which accelerometer instance is active
uint8_t _active_accel_instance ;
2013-05-04 12:25:59 -03:00
// the earths magnetic field
float _last_declination ;
2021-07-20 01:21:09 -03:00
Vector2f _mag_earth { 1 , 0 } ;
2012-08-21 23:19:51 -03:00
// whether we have GPS lock
bool _have_gps_lock ;
// the lat/lng where we last had GPS lock
int32_t _last_lat ;
int32_t _last_lng ;
2021-08-14 00:03:42 -03:00
uint32_t _last_pos_ms ;
2012-08-21 23:19:51 -03:00
// position offset from last GPS lock
float _position_offset_north ;
float _position_offset_east ;
// whether we have a position estimate
bool _have_position ;
// support for wind estimation
Vector3f _last_fuse ;
Vector3f _last_vel ;
uint32_t _last_wind_time ;
float _last_airspeed ;
2013-10-21 23:06:27 -03:00
uint32_t _last_consistent_heading ;
2012-08-21 23:19:51 -03:00
// estimated wind in m/s
Vector3f _wind ;
2014-05-15 04:09:18 -03:00
2021-07-20 01:21:09 -03:00
float _imu1_weight { 0.5f } ;
2014-10-31 20:19:11 -03:00
2014-05-15 04:09:18 -03:00
// last time AHRS failed in milliseconds
uint32_t _last_failure_ms ;
2015-04-27 21:26:36 -03:00
// time when DCM was last reset
uint32_t _last_startup_ms ;
2021-08-14 00:03:42 -03:00
// last origin we returned, for DCM fallback from EKF
Location last_origin ;
2021-08-19 23:44:05 -03:00
// Declare filter states for HPF and LPF used by complementary
// filter in AP_AHRS::groundspeed_vector
Vector2f _lp ; // ground vector low-pass filter
Vector2f _hp ; // ground vector high-pass filter
Vector2f _lastGndVelADS ; // previous HPF input
2021-10-05 00:08:54 -03:00
// pre-calculated trig cache:
float _sin_yaw ;
float _cos_yaw ;
2023-11-18 01:44:06 -04:00
uint32_t last_log_ms ;
2010-12-01 03:58:04 -04:00
} ;
2023-09-20 08:20:44 -03:00
# endif // AP_AHRS_DCM_ENABLED