@ -69,23 +69,23 @@ public:
@@ -69,23 +69,23 @@ public:
int8_t getPrimaryCoreIMUIndex ( void ) const ;
// Write the last calculated NE position relative to the reference point (m) for the specified instance.
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
// If a calculated solution is not available, use the best available data and return false
// If false returned, do not use for flight control
bool getPosNE ( int8_t instance , Vector2f & posNE ) const ;
// Write the last calculated D position relative to the reference point (m) for the specified instance.
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
// If a calculated solution is not available, use the best available data and return false
// If false returned, do not use for flight control
bool getPosD ( int8_t instance , float & posD ) const ;
// return NED velocity in m/s for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getVelNED ( int8_t instance , Vector3f & vel ) const ;
// Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
// This can be different to the z component of the EKF velocity state because it will fluctuate with height errors and corrections in the EKF
// but will always be kinematically consistent with the z component of the EKF position state
float getPosDownDerivative ( int8_t instance ) const ;
@ -94,15 +94,15 @@ public:
@@ -94,15 +94,15 @@ public:
void getAccelNED ( Vector3f & accelNED ) const ;
// return body axis gyro bias estimates in rad/sec for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getGyroBias ( int8_t instance , Vector3f & gyroBias ) const ;
// return accelerometer bias estimate in m/s/s
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getAccelBias ( int8_t instance , Vector3f & accelBias ) const ;
// return tilt error convergence metric for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getTiltError ( int8_t instance , float & ang ) const ;
// reset body axis gyro bias estimates
@ -110,7 +110,7 @@ public:
@@ -110,7 +110,7 @@ public:
// 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
// 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
bool resetHeightDatum ( void ) ;
@ -130,19 +130,19 @@ public:
@@ -130,19 +130,19 @@ public:
void getEkfControlLimits ( float & ekfGndSpdLimit , float & ekfNavVelGainScaler ) const ;
// return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis)
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getWind ( int8_t instance , Vector3f & wind ) const ;
// return earth magnetic field estimates in measurement units / 1000 for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getMagNED ( int8_t instance , Vector3f & magNED ) const ;
// return body magnetic field estimates in measurement units / 1000 for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getMagXYZ ( int8_t instance , Vector3f & magXYZ ) const ;
// return the magnetometer in use for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
uint8_t getActiveMag ( int8_t instance ) const ;
// Return estimated magnetometer offsets
@ -156,7 +156,7 @@ public:
@@ -156,7 +156,7 @@ public:
bool getLLH ( struct Location & loc ) const ;
// Return the latitude and longitude and height used to set the NED origin for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
// All NED positions calculated by the filter are relative to this location
// Returns false if the origin has not been set
bool getOriginLLH ( int8_t instance , struct Location & loc ) const ;
@ -172,7 +172,7 @@ public:
@@ -172,7 +172,7 @@ public:
bool getHAGL ( float & HAGL ) const ;
// return the Euler roll, pitch and yaw angle in radians for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getEulerAngles ( int8_t instance , Vector3f & eulers ) const ;
// return the transformation matrix from XYZ (body) to NED axes
@ -182,14 +182,14 @@ public:
@@ -182,14 +182,14 @@ public:
void getQuaternion ( int8_t instance , Quaternion & quat ) const ;
// return the innovations for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getInnovations ( int8_t index , Vector3f & velInnov , Vector3f & posInnov , Vector3f & magInnov , float & tasInnov , float & yawInnov ) const ;
// publish output observer angular, velocity and position tracking error
void getOutputTrackingError ( int8_t instance , Vector3f & error ) const ;
// return the innovation consistency test ratios for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getVariances ( int8_t instance , float & velVar , float & posVar , float & hgtVar , Vector3f & magVar , float & tasVar , Vector2f & offset ) const ;
// return the diagonals from the covariance matrix for the specified instance
@ -242,7 +242,7 @@ public:
@@ -242,7 +242,7 @@ public:
uint32_t getBodyFrameOdomDebug ( int8_t instance , Vector3f & velInnov , Vector3f & velInnovVar ) const ;
// return data for debugging optical flow fusion for the specified instance
// An out of range instance (eg -1) returns data for the the primary instance
// An out of range instance (eg -1) returns data for the primary instance
void getFlowDebug ( int8_t instance , float & varFlow , float & gndOffset , float & flowInnovX , float & flowInnovY , float & auxInnov , float & HAGL , float & rngInnov , float & range , float & gndOffsetErr ) const ;
/*
@ -277,7 +277,7 @@ public:
@@ -277,7 +277,7 @@ public:
/*
return the filter fault status as a bitmasked integer for the specified instance
An out of range instance ( eg - 1 ) returns data for the the primary instance
An out of range instance ( eg - 1 ) returns data for the primary instance
0 = quaternions are NaN
1 = velocities are NaN
2 = badly conditioned X magnetometer fusion
@ -291,7 +291,7 @@ public:
@@ -291,7 +291,7 @@ public:
/*
return filter timeout status as a bitmasked integer for the specified instance
An out of range instance ( eg - 1 ) returns data for the the primary instance
An out of range instance ( eg - 1 ) returns data for the primary instance
0 = position measurement timeout
1 = velocity measurement timeout
2 = height measurement timeout
@ -305,13 +305,13 @@ public:
@@ -305,13 +305,13 @@ public:
/*
return filter gps quality check status for the specified instance
An out of range instance ( eg - 1 ) returns data for the the primary instance
An out of range instance ( eg - 1 ) returns data for the primary instance
*/
void getFilterGpsStatus ( int8_t instance , nav_gps_status & faults ) const ;
/*
return filter status flags for the specified instance
An out of range instance ( eg - 1 ) returns data for the the primary instance
An out of range instance ( eg - 1 ) returns data for the primary instance
*/
void getFilterStatus ( int8_t instance , nav_filter_status & status ) const ;
@ -411,7 +411,7 @@ private:
@@ -411,7 +411,7 @@ private:
AP_Int8 _rngBcnDelay_ms ; // effective average delay of range beacon measurements rel to IMU (msec)
AP_Float _useRngSwSpd ; // Maximum horizontal ground speed to use range finder as the primary height source (m/s)
AP_Float _accBiasLim ; // Accelerometer bias limit (m/s/s)
AP_Int8 _magMask ; // Bitmask forcng specific EKF core instances to use simple heading magnetometer fusion.
AP_Int8 _magMask ; // Bitmask forci ng specific EKF core instances to use simple heading magnetometer fusion.
AP_Int8 _originHgtMode ; // Bitmask controlling post alignment correction and reporting of the EKF origin height.
AP_Float _visOdmVelErrMax ; // Observation 1-STD velocity error assumed for visual odometry sensor at lowest reported quality (m/s)
AP_Float _visOdmVelErrMin ; // Observation 1-STD velocity error assumed for visual odometry sensor at highest reported quality (m/s)