mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_AHRS: accept external position estimates into AHRS
This commit is contained in:
parent
0d77cfb6c3
commit
20412dc0db
@ -585,6 +585,9 @@ public:
|
||||
// false when no limiting is required
|
||||
virtual bool get_hgt_ctrl_limit(float &limit) const { return false; };
|
||||
|
||||
// Write position and quaternion data from an external navigation system
|
||||
virtual void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) { }
|
||||
|
||||
protected:
|
||||
AHRS_VehicleClass _vehicle_class;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user