2016-02-17 21:25:13 -04:00
# pragma once
2012-12-12 17:42:14 -04:00
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-19 03:34:12 -03:00
/*
2012-08-21 23:19:51 -03:00
* AHRS ( Attitude Heading Reference System ) interface for ArduPilot
*
*/
2012-03-19 03:34:12 -03:00
2015-08-11 03:28:42 -03:00
# include <AP_Math/AP_Math.h>
2012-03-19 03:34:12 -03:00
# include <inttypes.h>
2015-08-11 03:28:42 -03:00
# include <AP_Airspeed/AP_Airspeed.h>
# include <AP_InertialSensor/AP_InertialSensor.h>
2023-09-17 23:40:41 -03:00
# include <AP_Common/Location.h>
2012-03-19 03:34:12 -03:00
2013-02-19 05:50:57 -04:00
# define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
2014-10-21 09:40:16 -03:00
# define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter
# define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter
2013-02-19 05:50:57 -04:00
2021-08-18 07:20:46 -03:00
enum class GPSUse : uint8_t {
Disable = 0 ,
Enable = 1 ,
EnableWithHeight = 2 ,
} ;
2021-07-20 10:04:20 -03:00
class AP_AHRS_Backend
2012-03-19 03:34:12 -03:00
{
public :
2019-02-19 23:53:28 -04:00
2012-08-21 23:19:51 -03:00
// Constructor
2021-08-11 21:44:52 -03:00
AP_AHRS_Backend ( ) { }
2012-08-21 23:19:51 -03:00
2014-07-15 01:29:34 -03:00
// empty virtual destructor
2021-07-20 10:04:20 -03:00
virtual ~ AP_AHRS_Backend ( ) { }
2018-01-01 08:03:28 -04:00
2021-08-18 07:20:46 -03:00
CLASS_NO_COPY ( AP_AHRS_Backend ) ;
// structure to retrieve results from backends:
struct Estimates {
float roll_rad ;
float pitch_rad ;
float yaw_rad ;
Matrix3f dcm_matrix ;
Vector3f gyro_estimate ;
Vector3f gyro_drift ;
2022-07-26 21:21:01 -03:00
Vector3f accel_ef ;
2021-12-06 05:54:12 -04:00
Vector3f accel_bias ;
2023-09-17 23:40:41 -03:00
Location location ;
bool location_valid ;
bool get_location ( Location & loc ) const {
loc = location ;
return location_valid ;
} ;
2021-08-18 07:20:46 -03:00
} ;
2013-01-13 01:03:35 -04:00
// init sets up INS board orientation
2019-03-04 14:16:06 -04:00
virtual void init ( ) ;
2012-08-21 23:19:51 -03:00
2020-04-21 01:39:45 -03:00
// return the index of the primary core or -1 if no primary core selected
virtual int8_t get_primary_core_index ( ) const { return - 1 ; }
2016-09-03 04:54:36 -03:00
// get the index of the current primary accelerometer sensor
virtual uint8_t get_primary_accel_index ( void ) const {
2018-03-10 05:35:03 -04:00
return AP : : ins ( ) . get_primary_accel ( ) ;
2016-09-03 04:54:36 -03:00
}
// get the index of the current primary gyro sensor
virtual uint8_t get_primary_gyro_index ( void ) const {
2018-03-10 05:35:03 -04:00
return AP : : ins ( ) . get_primary_gyro ( ) ;
2016-09-03 04:54:36 -03:00
}
2019-02-19 23:53:28 -04:00
2012-08-21 23:19:51 -03:00
// Methods
2021-08-18 07:20:46 -03:00
virtual void update ( ) = 0 ;
virtual void get_results ( Estimates & results ) = 0 ;
2012-08-21 23:19:51 -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
virtual bool pre_arm_check ( bool requires_position , char * failure_msg , uint8_t failure_msg_len ) const = 0 ;
2015-09-23 04:29:43 -03:00
2019-02-19 23:52:55 -04:00
// check all cores providing consistent attitudes for prearm checks
2019-03-06 02:50:11 -04:00
virtual bool attitudes_consistent ( char * failure_msg , const uint8_t failure_msg_len ) const { return true ; }
2019-02-19 23:52:55 -04:00
2019-06-07 20:33:45 -03:00
// see if EKF lane switching is possible to avoid EKF failsafe
virtual void check_lane_switch ( void ) { }
2020-03-27 04:32:00 -03:00
2021-08-18 04:34:37 -03:00
// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed
virtual bool using_noncompass_for_yaw ( void ) const { return false ; }
2021-08-18 04:45:01 -03:00
// check if external nav is providing yaw
virtual bool using_extnav_for_yaw ( void ) const { return false ; }
2020-03-11 00:46:52 -03:00
// request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe
virtual void request_yaw_reset ( void ) { }
2020-03-27 04:32:00 -03:00
2020-06-17 03:35:07 -03:00
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
virtual void set_posvelyaw_source_set ( uint8_t source_set_idx ) { }
2014-10-28 08:22:48 -03:00
// reset the current gyro drift estimate
// should be called if gyro offsets are recalculated
virtual void reset_gyro_drift ( void ) = 0 ;
2012-08-21 23:19:51 -03:00
// reset the current attitude, used on new IMU calibration
2021-08-18 07:20:46 -03:00
virtual void reset ( ) = 0 ;
2019-02-19 23:53:28 -04:00
2019-06-17 19:24:34 -03:00
// get latest altitude estimate above ground level in meters and validity flag
2020-12-06 06:59:00 -04:00
virtual bool get_hagl ( float & height ) const WARN_IF_UNUSED { return false ; }
2018-01-05 21:25:04 -04:00
2012-08-21 23:19:51 -03:00
// return a wind estimation vector, in m/s
2023-01-12 03:12:01 -04:00
virtual bool wind_estimate ( Vector3f & wind ) const = 0 ;
2012-08-21 23:19:51 -03:00
2012-08-24 08:22:58 -03:00
// return an airspeed estimate if available. return true
// if we have an estimate
2021-08-18 07:20:46 -03:00
virtual bool airspeed_estimate ( float & airspeed_ret ) const WARN_IF_UNUSED { return false ; }
virtual bool airspeed_estimate ( uint8_t airspeed_index , float & airspeed_ret ) const { return false ; }
2012-08-24 08:22:58 -03:00
2013-07-19 22:11:57 -03:00
// return a true airspeed estimate (navigation airspeed) if
// available. return true if we have an estimate
2020-01-06 20:45:58 -04:00
bool airspeed_estimate_true ( float & airspeed_ret ) const WARN_IF_UNUSED {
2013-07-19 22:11:57 -03:00
if ( ! airspeed_estimate ( airspeed_ret ) ) {
return false ;
}
2020-01-06 20:45:58 -04:00
airspeed_ret * = get_EAS2TAS ( ) ;
2013-07-19 22:11:57 -03:00
return true ;
}
2020-11-20 17:40:19 -04:00
// return estimate of true airspeed vector in body frame in m/s
// returns false if estimate is unavailable
virtual bool airspeed_vector_true ( Vector3f & vec ) const WARN_IF_UNUSED {
return false ;
}
2013-07-19 22:11:57 -03:00
// get apparent to true airspeed ratio
2023-09-18 10:18:55 -03:00
static float get_EAS2TAS ( void ) ;
2013-07-19 22:11:57 -03:00
2013-06-26 07:46:26 -03:00
// return true if airspeed comes from an airspeed sensor, as
// opposed to an IMU estimate
2023-09-18 10:18:55 -03:00
static bool airspeed_sensor_enabled ( void ) {
2022-01-09 21:37:03 -04:00
# if AP_AIRSPEED_ENABLED
2020-07-27 00:28:20 -03:00
const AP_Airspeed * _airspeed = AP : : airspeed ( ) ;
2016-10-30 02:24:21 -03:00
return _airspeed ! = nullptr & & _airspeed - > use ( ) & & _airspeed - > healthy ( ) ;
2022-01-09 21:37:03 -04:00
# else
return false ;
# endif
2013-06-26 07:46:26 -03:00
}
2020-08-18 12:08:35 -03:00
// return true if airspeed comes from a specific airspeed sensor, as
// opposed to an IMU estimate
2023-09-18 10:18:55 -03:00
static bool airspeed_sensor_enabled ( uint8_t airspeed_index ) {
2022-01-09 21:37:03 -04:00
# if AP_AIRSPEED_ENABLED
2020-07-27 00:28:20 -03:00
const AP_Airspeed * _airspeed = AP : : airspeed ( ) ;
2020-08-18 12:08:35 -03:00
return _airspeed ! = nullptr & & _airspeed - > use ( airspeed_index ) & & _airspeed - > healthy ( airspeed_index ) ;
2022-01-09 21:37:03 -04:00
# else
return false ;
# endif
2020-08-18 12:08:35 -03:00
}
2013-03-29 03:23:22 -03:00
// return a ground vector estimate in meters/second, in North/East order
2021-08-19 23:44:05 -03:00
virtual Vector2f groundspeed_vector ( void ) = 0 ;
2013-03-29 03:23:22 -03:00
2014-01-03 20:15:34 -04:00
// return a ground velocity in meters/second, North/East/Down
// order. This will only be accurate if have_inertial_nav() is
2015-09-23 04:29:43 -03:00
// true
2019-03-12 06:47:09 -03:00
virtual bool get_velocity_NED ( Vector3f & vec ) const WARN_IF_UNUSED {
2015-09-23 04:29:43 -03:00
return false ;
}
2014-01-03 20:15:34 -04:00
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
virtual bool get_vert_pos_rate_D ( float & velocity ) const = 0 ;
2021-08-18 07:20:46 -03:00
2016-01-04 19:57:17 -04:00
// returns the estimated magnetic field offsets in body frame
2019-03-12 06:47:09 -03:00
virtual bool get_mag_field_correction ( Vector3f & ret ) const WARN_IF_UNUSED {
2016-01-04 19:57:17 -04:00
return false ;
}
2021-08-18 07:20:46 -03:00
virtual bool get_mag_field_NED ( Vector3f & vec ) const {
return false ;
}
virtual bool get_mag_offsets ( uint8_t mag_idx , Vector3f & magOffsets ) const {
return false ;
}
//
2023-02-02 18:58:38 -04:00
virtual bool set_origin ( const Location & loc ) {
2021-08-18 07:20:46 -03:00
return false ;
}
2023-02-02 18:58:38 -04:00
virtual bool get_origin ( Location & ret ) const = 0 ;
2021-08-18 07:20:46 -03:00
2017-01-30 15:06:13 -04:00
// return a position relative to origin in meters, North/East/Down
// order. This will only be accurate if have_inertial_nav() is
// true
2019-03-12 06:47:09 -03:00
virtual bool get_relative_position_NED_origin ( Vector3f & vec ) const WARN_IF_UNUSED {
2017-01-30 15:06:13 -04:00
return false ;
}
// return a position relative to origin in meters, North/East
// order. Return true if estimate is valid
2019-03-12 06:47:09 -03:00
virtual bool get_relative_position_NE_origin ( Vector2f & vecNE ) const WARN_IF_UNUSED {
2016-07-09 08:36:09 -03:00
return false ;
}
2017-01-30 15:06:13 -04:00
// return a Down position relative to origin in meters
2016-07-09 08:36:09 -03:00
// Return true if estimate is valid
2019-03-12 06:47:09 -03:00
virtual bool get_relative_position_D_origin ( float & posD ) const WARN_IF_UNUSED {
2016-07-09 08:36:09 -03:00
return false ;
}
2013-09-08 21:17:45 -03:00
// return ground speed estimate in meters/second. Used by ground vehicles.
2016-05-31 02:55:41 -03:00
float groundspeed ( void ) {
return groundspeed_vector ( ) . length ( ) ;
2013-09-08 21:17:45 -03:00
}
2013-03-28 23:48:25 -03:00
// return true if we will use compass for yaw
2021-07-25 21:32:10 -03:00
virtual bool use_compass ( void ) = 0 ;
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
virtual bool get_quaternion ( Quaternion & quat ) const WARN_IF_UNUSED = 0 ;
2013-07-19 22:11:57 -03:00
2014-01-03 20:15:34 -04:00
// return true if the AHRS object supports inertial navigation,
// with very accurate position and velocity
2015-09-23 04:29:43 -03:00
virtual bool have_inertial_nav ( void ) const {
return false ;
}
2014-01-03 20:15:34 -04:00
2014-05-15 04:09:18 -03:00
// is the AHRS subsystem healthy?
2015-01-31 22:31:24 -04:00
virtual bool healthy ( void ) const = 0 ;
2014-05-15 04:09:18 -03:00
2014-10-02 01:43:46 -03:00
// true if the AHRS has completed initialisation
2015-09-23 04:29:43 -03:00
virtual bool initialised ( void ) const {
return true ;
} ;
2021-08-18 07:20:46 -03:00
virtual bool started ( void ) const {
return initialised ( ) ;
} ;
2014-09-29 05:37:14 -03:00
2015-09-23 04:46:51 -03:00
// return the amount of yaw angle change due to the last yaw angle reset in radians
2015-09-24 03:51:21 -03:00
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
2019-12-10 05:32:52 -04:00
virtual uint32_t getLastYawResetAngle ( float & yawAng ) {
2015-10-29 05:31:02 -03:00
return 0 ;
2015-09-23 04:46:51 -03:00
} ;
2015-10-29 02:18:04 -03:00
// return the amount of NE position change in metres due to the last reset
// returns the time of the last reset or 0 if no reset has ever occurred
2019-12-10 05:32:52 -04:00
virtual uint32_t getLastPosNorthEastReset ( Vector2f & pos ) WARN_IF_UNUSED {
2015-10-29 02:18:04 -03:00
return 0 ;
} ;
// return the amount of NE velocity change in metres/sec due to the last reset
// returns the time of the last reset or 0 if no reset has ever occurred
2019-03-12 06:47:09 -03:00
virtual uint32_t getLastVelNorthEastReset ( Vector2f & vel ) const WARN_IF_UNUSED {
2015-10-29 02:18:04 -03:00
return 0 ;
} ;
2016-11-22 01:28:14 -04:00
// return the amount of vertical position change due to the last reset in meters
// returns the time of the last reset or 0 if no reset has ever occurred
2019-12-10 05:32:52 -04:00
virtual uint32_t getLastPosDownReset ( float & posDelta ) WARN_IF_UNUSED {
2016-11-22 01:28:14 -04:00
return 0 ;
} ;
2015-09-23 04:46:51 -03:00
// Resets the baro so that it reads zero at the current height
// Resets the EKF height to zero
// Adjusts the EKf origin height so that the EKF height + origin height is the same as before
// Returns true if the height datum reset has been performed
// If using a range finder for height no reset is performed and it returns false
2019-03-12 06:47:09 -03:00
virtual bool resetHeightDatum ( void ) WARN_IF_UNUSED {
2015-09-23 04:46:51 -03:00
return false ;
}
2019-02-19 23:53:28 -04:00
2019-10-04 22:04:00 -03:00
// return the innovations for the specified instance
// An out of range instance (eg -1) returns data for the primary instance
virtual bool get_innovations ( Vector3f & velInnov , Vector3f & posInnov , Vector3f & magInnov , float & tasInnov , float & yawInnov ) const {
return false ;
}
2023-05-14 21:44:18 -03:00
virtual bool get_filter_status ( union nav_filter_status & status ) const {
2021-08-18 07:20:46 -03:00
return false ;
}
2016-09-21 18:00:21 -03:00
// get_variances - provides the innovations normalised using the innovation variance where a value of 0
2022-02-04 20:49:32 -04:00
// indicates perfect consistency between the measurement and the EKF solution and a value of 1 is the maximum
2017-11-27 08:08:33 -04:00
// inconsistency that will be accepted by the filter
2016-09-21 18:00:21 -03:00
// boolean false is returned if variances are not available
2020-10-20 01:23:42 -03:00
virtual bool get_variances ( float & velVar , float & posVar , float & hgtVar , Vector3f & magVar , float & tasVar ) const {
2016-09-21 18:00:21 -03:00
return false ;
}
2019-02-19 23:53:28 -04:00
2020-10-13 02:21:07 -03:00
// get a source's velocity innovations. source should be from 0 to 7 (see AP_NavEKF_Source::SourceXY)
// returns true on success and results are placed in innovations and variances arguments
virtual bool get_vel_innovations_and_variances_for_source ( uint8_t source , Vector3f & innovations , Vector3f & variances ) const WARN_IF_UNUSED {
return false ;
}
2022-07-08 01:15:35 -03:00
virtual void send_ekf_status_report ( class GCS_MAVLINK & link ) const = 0 ;
2021-08-18 07:20:46 -03:00
2017-12-07 00:51:28 -04:00
// get_hgt_ctrl_limit - get maximum height to be observed by the
// control loops in meters and a validity flag. It will return
// false when no limiting is required
2019-03-12 06:47:09 -03:00
virtual bool get_hgt_ctrl_limit ( float & limit ) const WARN_IF_UNUSED { return false ; } ;
2017-12-07 00:51:28 -04:00
2020-06-22 00:15:07 -03:00
// Set to true if the terrain underneath is stable enough to be used as a height reference
// this is not related to terrain following
virtual void set_terrain_hgt_stable ( bool stable ) { }
2023-01-03 06:19:00 -04:00
virtual void get_control_limits ( float & ekfGndSpdLimit , float & controlScaleXY ) const = 0 ;
2013-05-12 22:24:48 -03:00
} ;