AP_NavEKF2: getLastYawResetAngle returns last reset time
This commit is contained in:
parent
b5c49e0792
commit
015f700bc0
@ -771,9 +771,8 @@ bool NavEKF2::getHeightControlLimit(float &height) const
|
|||||||
}
|
}
|
||||||
|
|
||||||
// return the amount of yaw angle change due to the last yaw angle reset in radians
|
// 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
|
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
|
||||||
// this function should not have more than one client
|
uint32_t NavEKF2::getLastYawResetAngle(float &yawAng)
|
||||||
bool NavEKF2::getLastYawResetAngle(float &yawAng)
|
|
||||||
{
|
{
|
||||||
if (!core) {
|
if (!core) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -214,9 +214,8 @@ public:
|
|||||||
bool getHeightControlLimit(float &height) const;
|
bool getHeightControlLimit(float &height) const;
|
||||||
|
|
||||||
// return the amount of yaw angle change due to the last yaw angle reset in radians
|
// 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
|
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
|
||||||
// this function should not have more than one client
|
uint32_t getLastYawResetAngle(float &yawAng);
|
||||||
bool getLastYawResetAngle(float &yawAng);
|
|
||||||
|
|
||||||
// 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); }
|
||||||
|
@ -4015,10 +4015,12 @@ Quaternion NavEKF2_core::calcQuatAndFieldStates(float roll, float pitch)
|
|||||||
// store the yaw change so that it can be retrieved externally for use by the control loops to prevent yaw disturbances following a reset
|
// store the yaw change so that it can be retrieved externally for use by the control loops to prevent yaw disturbances following a reset
|
||||||
Vector3f tempEuler;
|
Vector3f tempEuler;
|
||||||
stateStruct.quat.to_euler(tempEuler.x, tempEuler.y, tempEuler.z);
|
stateStruct.quat.to_euler(tempEuler.x, tempEuler.y, tempEuler.z);
|
||||||
yawResetAngle = wrap_PI(yaw - tempEuler.z);
|
// this check ensures we accumulate the resets that occur within a single iteration of the EKF
|
||||||
// set the flag to indicate that an in-flight yaw reset has been performed
|
if (imuSampleTime_ms != lastYawReset_ms) {
|
||||||
// this will be cleared when the reset value is retrieved
|
yawResetAngle = 0.0f;
|
||||||
yawResetAngleWaiting = true;
|
}
|
||||||
|
yawResetAngle += wrap_PI(yaw - tempEuler.z);
|
||||||
|
lastYawReset_ms = imuSampleTime_ms;
|
||||||
// calculate an initial quaternion using the new yaw value
|
// calculate an initial quaternion using the new yaw value
|
||||||
initQuat.from_euler(roll, pitch, yaw);
|
initQuat.from_euler(roll, pitch, yaw);
|
||||||
} else {
|
} else {
|
||||||
@ -4230,7 +4232,7 @@ void NavEKF2_core::InitialiseVariables()
|
|||||||
highYawRate = false;
|
highYawRate = false;
|
||||||
yawRateFilt = 0.0f;
|
yawRateFilt = 0.0f;
|
||||||
yawResetAngle = 0.0f;
|
yawResetAngle = 0.0f;
|
||||||
yawResetAngleWaiting = false;
|
lastYawReset_ms = 0;
|
||||||
tiltErrFilt = 1.0f;
|
tiltErrFilt = 1.0f;
|
||||||
tiltAlignComplete = false;
|
tiltAlignComplete = false;
|
||||||
yawAlignComplete = false;
|
yawAlignComplete = false;
|
||||||
@ -4810,18 +4812,11 @@ void NavEKF2_core::alignMagStateDeclination()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// return the amount of yaw angle change due to the last yaw angle reset in radians
|
// 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
|
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
|
||||||
// this function should not have more than one client
|
uint32_t NavEKF2_core::getLastYawResetAngle(float &yawAng)
|
||||||
bool NavEKF2_core::getLastYawResetAngle(float &yawAng)
|
|
||||||
{
|
{
|
||||||
if (yawResetAngleWaiting) {
|
yawAng = yawResetAngle;
|
||||||
yawAng = yawResetAngle;
|
return lastYawReset_ms;
|
||||||
yawResetAngleWaiting = false;
|
|
||||||
return true;
|
|
||||||
} else {
|
|
||||||
yawAng = yawResetAngle;
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Fuse compass measurements usinga simple declination observation model that doesn't use magnetic field states
|
// Fuse compass measurements usinga simple declination observation model that doesn't use magnetic field states
|
||||||
|
@ -207,9 +207,8 @@ public:
|
|||||||
bool getHeightControlLimit(float &height) const;
|
bool getHeightControlLimit(float &height) const;
|
||||||
|
|
||||||
// return the amount of yaw angle change due to the last yaw angle reset in radians
|
// 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
|
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
|
||||||
// this function should not have more than one client
|
uint32_t getLastYawResetAngle(float &yawAng);
|
||||||
bool getLastYawResetAngle(float &yawAng);
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// Reference to the global EKF frontend for parameters
|
// Reference to the global EKF frontend for parameters
|
||||||
@ -668,7 +667,7 @@ private:
|
|||||||
float yawRateFilt; // filtered yaw rate used to determine when the vehicle is doing rapid yaw rotation where gyro scel factor errors could cause loss of heading reference
|
float yawRateFilt; // filtered yaw rate used to determine when the vehicle is doing rapid yaw rotation where gyro scel factor errors could cause loss of heading reference
|
||||||
bool useGpsVertVel; // true if GPS vertical velocity should be used
|
bool useGpsVertVel; // true if GPS vertical velocity should be used
|
||||||
float yawResetAngle; // Change in yaw angle due to last in-flight yaw reset in radians. A positive value means the yaw angle has increased.
|
float yawResetAngle; // Change in yaw angle due to last in-flight yaw reset in radians. A positive value means the yaw angle has increased.
|
||||||
bool yawResetAngleWaiting; // true when the yaw reset angle has been updated and has not been retrieved via the getLastYawResetAngle() function
|
uint32_t lastYawReset_ms; // System time at which the last yaw reset occurred. Returned by getLastYawResetAngle
|
||||||
Vector3f tiltErrVec; // Vector of most recent attitude error correction from Vel,Pos fusion
|
Vector3f tiltErrVec; // Vector of most recent attitude error correction from Vel,Pos fusion
|
||||||
float tiltErrFilt; // Filtered tilt error metric
|
float tiltErrFilt; // Filtered tilt error metric
|
||||||
bool tiltAlignComplete; // true when tilt alignment is complete
|
bool tiltAlignComplete; // true when tilt alignment is complete
|
||||||
|
Loading…
Reference in New Issue
Block a user