AP_AHRS: Update function descriptions in header

This commit is contained in:
Michael du Breuil 2019-06-17 15:24:34 -07:00 committed by WickedShell
parent 0ed3c547fd
commit 0a7cf77de4

View File

@ -235,10 +235,10 @@ public:
int32_t pitch_sensor; int32_t pitch_sensor;
int32_t yaw_sensor; int32_t yaw_sensor;
// return a smoothed and corrected gyro vector // return a smoothed and corrected gyro vector in radians/second
virtual const Vector3f &get_gyro(void) const = 0; virtual const Vector3f &get_gyro(void) const = 0;
// return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet) // return a smoothed and corrected gyro vector in radians/second using the latest ins data (which may not have been consumed by the EKF yet)
Vector3f get_gyro_latest(void) const; Vector3f get_gyro_latest(void) const;
// return the current estimate of the gyro drift // return the current estimate of the gyro drift
@ -280,6 +280,7 @@ public:
// otherwise false. This call fills in lat, lng and alt // otherwise false. This call fills in lat, lng and alt
virtual bool get_position(struct Location &loc) const = 0; virtual bool get_position(struct Location &loc) const = 0;
// get latest altitude estimate above ground level in meters and validity flag
virtual bool get_hagl(float &height) const { return false; } virtual bool get_hagl(float &height) const { return false; }
// return a wind estimation vector, in m/s // return a wind estimation vector, in m/s