mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_AHRS: getLastYawResetAngle returns reset time
This commit is contained in:
parent
015f700bc0
commit
9f59b6f7b5
@ -400,9 +400,8 @@ public:
|
||||
};
|
||||
|
||||
// return the amount of yaw angle change due to the last yaw angle reset in radians
|
||||
// returns true if a reset yaw angle has been updated and not queried
|
||||
// this function should not have more than one client
|
||||
virtual bool getLastYawResetAngle(float &yawAng) {
|
||||
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
|
||||
virtual uint32_t getLastYawResetAngle(float &yawAng) {
|
||||
return false;
|
||||
};
|
||||
|
||||
|
@ -679,9 +679,8 @@ const char *AP_AHRS_NavEKF::prearm_failure_reason(void) const
|
||||
}
|
||||
|
||||
// return the amount of yaw angle change due to the last yaw angle reset in radians
|
||||
// returns true if a reset yaw angle has been updated and not queried
|
||||
// this function should not have more than one client
|
||||
bool AP_AHRS_NavEKF::getLastYawResetAngle(float &yawAng)
|
||||
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
|
||||
uint32_t AP_AHRS_NavEKF::getLastYawResetAngle(float &yawAng)
|
||||
{
|
||||
switch (ekf_type()) {
|
||||
case 1:
|
||||
|
@ -143,9 +143,8 @@ public:
|
||||
const char *prearm_failure_reason(void) const override;
|
||||
|
||||
// return the amount of yaw angle change due to the last yaw angle reset in radians
|
||||
// returns true if a reset yaw angle has been updated and not queried
|
||||
// this function should not have more than one client
|
||||
bool getLastYawResetAngle(float &yawAng);
|
||||
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
|
||||
uint32_t getLastYawResetAngle(float &yawAng);
|
||||
|
||||
// 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