|
|
@ -193,6 +193,10 @@ public: |
|
|
|
// 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) const; |
|
|
|
uint32_t getLastVelNorthEastReset(Vector2f &vel) const; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// return the amount of vertical position change due to the last reset in meters
|
|
|
|
|
|
|
|
// returns the time of the last reset or 0 if no reset has ever occurred
|
|
|
|
|
|
|
|
uint32_t getLastPosDownReset(float &posDelta) const; |
|
|
|
|
|
|
|
|
|
|
|
// 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
|
|
|
|