|
|
@ -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
|
|
|
|