mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AHRS: make get_error_rp and get_error_yaw const
This commit is contained in:
parent
18a73d8630
commit
c6f71ea2e0
@ -217,11 +217,11 @@ public:
|
||||
|
||||
// return the average size of the roll/pitch error estimate
|
||||
// since last call
|
||||
virtual float get_error_rp(void) = 0;
|
||||
virtual float get_error_rp(void) const = 0;
|
||||
|
||||
// return the average size of the yaw error estimate
|
||||
// since last call
|
||||
virtual float get_error_yaw(void) = 0;
|
||||
virtual float get_error_yaw(void) const = 0;
|
||||
|
||||
// return a DCM rotation matrix representing our current
|
||||
// attitude
|
||||
|
@ -193,12 +193,12 @@ bool AP_AHRS_NavEKF::get_position(struct Location &loc) const
|
||||
}
|
||||
|
||||
// status reporting of estimated errors
|
||||
float AP_AHRS_NavEKF::get_error_rp(void)
|
||||
float AP_AHRS_NavEKF::get_error_rp(void) const
|
||||
{
|
||||
return AP_AHRS_DCM::get_error_rp();
|
||||
}
|
||||
|
||||
float AP_AHRS_NavEKF::get_error_yaw(void)
|
||||
float AP_AHRS_NavEKF::get_error_yaw(void) const
|
||||
{
|
||||
return AP_AHRS_DCM::get_error_yaw();
|
||||
}
|
||||
|
@ -64,8 +64,8 @@ public:
|
||||
bool get_position(struct Location &loc) const;
|
||||
|
||||
// status reporting of estimated error
|
||||
float get_error_rp(void);
|
||||
float get_error_yaw(void);
|
||||
float get_error_rp(void) const;
|
||||
float get_error_yaw(void) const;
|
||||
|
||||
// return a wind estimation vector, in m/s
|
||||
Vector3f wind_estimate(void);
|
||||
|
Loading…
Reference in New Issue
Block a user