mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Add accessor function for yaw alignment status
This commit is contained in:
parent
1dc79f0be8
commit
6a603019d5
|
@ -2022,3 +2022,12 @@ void NavEKF3::writeDefaultAirSpeed(float airspeed, float uncertainty)
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
// returns true when the yaw angle has been aligned
|
||||
bool NavEKF3::yawAlignmentComplete(void) const
|
||||
{
|
||||
if (!core) {
|
||||
return false;
|
||||
}
|
||||
return core[primary].have_aligned_yaw();
|
||||
}
|
||||
|
|
|
@ -373,6 +373,9 @@ public:
|
|||
// parameter conversion
|
||||
void convert_parameters();
|
||||
|
||||
// returns true when the yaw angle has been aligned
|
||||
bool yawAlignmentComplete(void) const;
|
||||
|
||||
private:
|
||||
uint8_t num_cores; // number of allocated cores
|
||||
uint8_t primary; // current primary core
|
||||
|
|
Loading…
Reference in New Issue