AP_NavEKF2: constify getLastPosNorthEastReset
Also constify getLastVelNorthEastReset
This commit is contained in:
parent
3f29365cae
commit
94adaba305
@ -819,20 +819,20 @@ uint32_t NavEKF2::getLastYawResetAngle(float &yawAng) const
|
|||||||
|
|
||||||
// return the amount of NE position change due to the last position reset in metres
|
// return the amount of NE position change due to the last position reset in metres
|
||||||
// returns the time of the last reset or 0 if no reset has ever occurred
|
// returns the time of the last reset or 0 if no reset has ever occurred
|
||||||
uint32_t NavEKF2::getLastPosNorthEastReset(Vector2f &pos)
|
uint32_t NavEKF2::getLastPosNorthEastReset(Vector2f &pos) const
|
||||||
{
|
{
|
||||||
if (!core) {
|
if (!core) {
|
||||||
return false;
|
return 0;
|
||||||
}
|
}
|
||||||
return core->getLastPosNorthEastReset(pos);
|
return core->getLastPosNorthEastReset(pos);
|
||||||
}
|
}
|
||||||
|
|
||||||
// return the amount of NE velocity change due to the last velocity reset in metres/sec
|
// return the amount of NE velocity change due to the last velocity reset in metres/sec
|
||||||
// returns the time of the last reset or 0 if no reset has ever occurred
|
// returns the time of the last reset or 0 if no reset has ever occurred
|
||||||
uint32_t NavEKF2::getLastVelNorthEastReset(Vector2f &vel)
|
uint32_t NavEKF2::getLastVelNorthEastReset(Vector2f &vel) const
|
||||||
{
|
{
|
||||||
if (!core) {
|
if (!core) {
|
||||||
return false;
|
return 0;
|
||||||
}
|
}
|
||||||
return core->getLastVelNorthEastReset(vel);
|
return core->getLastVelNorthEastReset(vel);
|
||||||
}
|
}
|
||||||
|
@ -229,11 +229,11 @@ public:
|
|||||||
|
|
||||||
// return the amount of NE position change due to the last position reset in metres
|
// return the amount of NE position change due to the last position reset in metres
|
||||||
// returns the time of the last reset or 0 if no reset has ever occurred
|
// 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 due to the last velocity reset in metres/sec
|
// return the amount of NE velocity change due to the last velocity reset in metres/sec
|
||||||
// returns the time of the last reset or 0 if no reset has ever occurred
|
// 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;
|
||||||
|
|
||||||
// allow the enable flag to be set by Replay
|
// allow the enable flag to be set by Replay
|
||||||
void set_enable(bool enable) { _enable.set(enable); }
|
void set_enable(bool enable) { _enable.set(enable); }
|
||||||
|
@ -130,7 +130,7 @@ uint32_t NavEKF2_core::getLastYawResetAngle(float &yawAng) const
|
|||||||
|
|
||||||
// return the amount of NE position change due to the last position reset in metres
|
// return the amount of NE position change due to the last position reset in metres
|
||||||
// returns the time of the last reset or 0 if no reset has ever occurred
|
// returns the time of the last reset or 0 if no reset has ever occurred
|
||||||
uint32_t NavEKF2_core::getLastPosNorthEastReset(Vector2f &pos)
|
uint32_t NavEKF2_core::getLastPosNorthEastReset(Vector2f &pos) const
|
||||||
{
|
{
|
||||||
pos = posResetNE;
|
pos = posResetNE;
|
||||||
return lastPosReset_ms;
|
return lastPosReset_ms;
|
||||||
@ -138,7 +138,7 @@ uint32_t NavEKF2_core::getLastPosNorthEastReset(Vector2f &pos)
|
|||||||
|
|
||||||
// return the amount of NE velocity change due to the last velocity reset in metres/sec
|
// return the amount of NE velocity change due to the last velocity reset in metres/sec
|
||||||
// returns the time of the last reset or 0 if no reset has ever occurred
|
// returns the time of the last reset or 0 if no reset has ever occurred
|
||||||
uint32_t NavEKF2_core::getLastVelNorthEastReset(Vector2f &vel)
|
uint32_t NavEKF2_core::getLastVelNorthEastReset(Vector2f &vel) const
|
||||||
{
|
{
|
||||||
vel = velResetNE;
|
vel = velResetNE;
|
||||||
return lastVelReset_ms;
|
return lastVelReset_ms;
|
||||||
|
@ -250,11 +250,11 @@ public:
|
|||||||
|
|
||||||
// return the amount of NE position change due to the last position reset in metres
|
// return the amount of NE position change due to the last position reset in metres
|
||||||
// returns the time of the last reset or 0 if no reset has ever occurred
|
// 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 due to the last velocity reset in metres/sec
|
// return the amount of NE velocity change due to the last velocity reset in metres/sec
|
||||||
// returns the time of the last reset or 0 if no reset has ever occurred
|
// 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;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// Reference to the global EKF frontend for parameters
|
// Reference to the global EKF frontend for parameters
|
||||||
|
Loading…
Reference in New Issue
Block a user