AP_AHRS: constify getLastPosNorthEastReset
Also constify getLastVelNortEastReset
This commit is contained in:
parent
52ed075405
commit
4e959ef6f9
@ -394,13 +394,13 @@ public:
|
||||
|
||||
// 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
|
||||
virtual uint32_t getLastPosNorthEastReset(Vector2f &pos) {
|
||||
virtual uint32_t getLastPosNorthEastReset(Vector2f &pos) const {
|
||||
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
|
||||
virtual uint32_t getLastVelNorthEastReset(Vector2f &vel) {
|
||||
virtual uint32_t getLastVelNorthEastReset(Vector2f &vel) const {
|
||||
return 0;
|
||||
};
|
||||
|
||||
|
@ -742,7 +742,7 @@ uint32_t AP_AHRS_NavEKF::getLastYawResetAngle(float &yawAng) const
|
||||
|
||||
// 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
|
||||
uint32_t AP_AHRS_NavEKF::getLastPosNorthEastReset(Vector2f &pos)
|
||||
uint32_t AP_AHRS_NavEKF::getLastPosNorthEastReset(Vector2f &pos) const
|
||||
{
|
||||
switch (ekf_type()) {
|
||||
case 1:
|
||||
@ -755,7 +755,7 @@ uint32_t AP_AHRS_NavEKF::getLastPosNorthEastReset(Vector2f &pos)
|
||||
|
||||
// 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
|
||||
uint32_t AP_AHRS_NavEKF::getLastVelNorthEastReset(Vector2f &vel)
|
||||
uint32_t AP_AHRS_NavEKF::getLastVelNorthEastReset(Vector2f &vel) const
|
||||
{
|
||||
switch (ekf_type()) {
|
||||
case 1:
|
||||
|
@ -169,11 +169,11 @@ public:
|
||||
|
||||
// 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
|
||||
uint32_t getLastPosNorthEastReset(Vector2f &pos);
|
||||
uint32_t getLastPosNorthEastReset(Vector2f &pos) const;
|
||||
|
||||
// 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
|
||||
uint32_t getLastVelNorthEastReset(Vector2f &vel);
|
||||
uint32_t getLastVelNorthEastReset(Vector2f &vel) const;
|
||||
|
||||
// Resets the baro so that it reads zero at the current height
|
||||
// Resets the EKF height to zero
|
||||
|
Loading…
Reference in New Issue
Block a user