mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_NavEKF2: add method to check if ext nav is used for yaw
This commit is contained in:
parent
916de076ec
commit
fc9ff2b09a
@ -1612,3 +1612,12 @@ void NavEKF2::writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, c
|
||||
}
|
||||
}
|
||||
|
||||
// check if external navigation is being used for yaw observation
|
||||
bool NavEKF2::isExtNavUsedForYaw() const
|
||||
{
|
||||
if (core) {
|
||||
return core[primary].isExtNavUsedForYaw();
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -352,6 +352,9 @@ public:
|
||||
// write EKF information to on-board logs
|
||||
void Log_Write();
|
||||
|
||||
// check if external navigation is being used for yaw observation
|
||||
bool isExtNavUsedForYaw(void) const;
|
||||
|
||||
private:
|
||||
uint8_t num_cores; // number of allocated cores
|
||||
uint8_t primary; // current primary core
|
||||
|
@ -616,3 +616,9 @@ void NavEKF2_core::getOutputTrackingError(Vector3f &error) const
|
||||
error = outputTrackError;
|
||||
}
|
||||
|
||||
// return true when external nav data is also being used as a yaw observation
|
||||
bool NavEKF2_core::isExtNavUsedForYaw()
|
||||
{
|
||||
return extNavUsedForYaw;
|
||||
}
|
||||
|
||||
|
@ -324,6 +324,9 @@ public:
|
||||
*/
|
||||
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms);
|
||||
|
||||
// return true when external nav data is also being used as a yaw observation
|
||||
bool isExtNavUsedForYaw(void);
|
||||
|
||||
private:
|
||||
// Reference to the global EKF frontend for parameters
|
||||
NavEKF2 *frontend;
|
||||
|
Loading…
Reference in New Issue
Block a user