From 7a6f671659601a667c18f79b5cc85516e4268302 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 24 Feb 2014 18:24:10 +1100 Subject: [PATCH] AP_GPS: added have_vertical_velocity() function for use by EKF --- libraries/AP_GPS/GPS.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_GPS/GPS.h b/libraries/AP_GPS/GPS.h index 62dd119bcf..c6fe1519fe 100644 --- a/libraries/AP_GPS/GPS.h +++ b/libraries/AP_GPS/GPS.h @@ -142,8 +142,8 @@ public: // return last fix time since the 1/1/1970 in microseconds uint64_t time_epoch_usec(void); - // return true if the GPS supports raw velocity values - + // return true if the GPS supports vertical velocity values + bool have_vertical_velocity(void) const { return _have_raw_velocity; } protected: AP_HAL::UARTDriver *_port; ///< port the GPS is attached to