From 0a7cf77de486844550de28630a4b02ac6c485462 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 17 Jun 2019 15:24:34 -0700 Subject: [PATCH] AP_AHRS: Update function descriptions in header --- libraries/AP_AHRS/AP_AHRS.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index fd4bc4d62a..c713e915fe 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -235,10 +235,10 @@ public: int32_t pitch_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; - // 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; // return the current estimate of the gyro drift @@ -280,6 +280,7 @@ public: // otherwise false. This call fills in lat, lng and alt 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; } // return a wind estimation vector, in m/s