mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: Publish the EKF position and velocity reset deltas
This commit is contained in:
parent
74da4d8e57
commit
f67f6b01f4
|
@ -392,6 +392,18 @@ public:
|
||||||
return false;
|
return false;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// 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) {
|
||||||
|
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) {
|
||||||
|
return 0;
|
||||||
|
};
|
||||||
|
|
||||||
// Resets the baro so that it reads zero at the current height
|
// Resets the baro so that it reads zero at the current height
|
||||||
// Resets the EKF height to zero
|
// 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
|
||||||
|
|
|
@ -740,6 +740,32 @@ uint32_t AP_AHRS_NavEKF::getLastYawResetAngle(float &yawAng)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// 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)
|
||||||
|
{
|
||||||
|
switch (ekf_type()) {
|
||||||
|
case 1:
|
||||||
|
return EKF1.getLastPosNorthEastReset(pos);
|
||||||
|
case 2:
|
||||||
|
return EKF2.getLastPosNorthEastReset(pos);
|
||||||
|
}
|
||||||
|
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
|
||||||
|
uint32_t AP_AHRS_NavEKF::getLastVelNorthEastReset(Vector2f &vel)
|
||||||
|
{
|
||||||
|
switch (ekf_type()) {
|
||||||
|
case 1:
|
||||||
|
return EKF1.getLastVelNorthEastReset(vel);
|
||||||
|
case 2:
|
||||||
|
return EKF2.getLastVelNorthEastReset(vel);
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
// Resets the baro so that it reads zero at the current height
|
// Resets the baro so that it reads zero at the current height
|
||||||
// Resets the EKF height to zero
|
// 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
|
||||||
|
|
|
@ -167,6 +167,14 @@ public:
|
||||||
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
|
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
|
||||||
uint32_t getLastYawResetAngle(float &yawAng);
|
uint32_t getLastYawResetAngle(float &yawAng);
|
||||||
|
|
||||||
|
// 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);
|
||||||
|
|
||||||
|
// 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);
|
||||||
|
|
||||||
// Resets the baro so that it reads zero at the current height
|
// Resets the baro so that it reads zero at the current height
|
||||||
// Resets the EKF height to zero
|
// 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
|
||||||
|
|
Loading…
Reference in New Issue