diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 6a76a6e837..a633efa804 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -3602,17 +3602,17 @@ void NavEKF::resetGyroBias(void) } -// Commands the EKF to not use GPS. It returns true if the command has been accepted. +// Commands the EKF to not use GPS. // This command must be sent prior to arming as it will only be actioned when the filter is in static mode // This command is forgotten by the EKF each time it goes back into static mode (eg the vehicle disarms) +// Returns 0 if command rejected +// Returns 1 if attitude, vertical velocity and vertical position will be provided +// Returns 2 if attitude, 3D-velocity, vertical position and relative horizontal position will be provided uint8_t NavEKF::setInhibitGPS(void) { - // Ignore request if not in in static mode (when armed) if(!staticMode) { return 0; } - // If we have received flow sensor data in the last second then indicate that we can do relative position - // otherwise indicate we can provide attitude and height only if (useOptFlow()) { gpsInhibitMode = 2; return 2; diff --git a/libraries/AP_NavEKF/AP_NavEKF.h b/libraries/AP_NavEKF/AP_NavEKF.h index 9ff1483af8..6e7ab67ab8 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.h +++ b/libraries/AP_NavEKF/AP_NavEKF.h @@ -114,9 +114,12 @@ public: // reset body axis gyro bias estimates void resetGyroBias(void); - // Commands the EKF to not use GPS. It returns true if the command has been accepted. + // Commands the EKF to not use GPS. // This command must be sent prior to arming as it will only be actioned when the filter is in static mode // This command is forgotten by the EKF each time it goes back into static mode (eg the vehicle disarms) + // Returns 0 if command rejected + // Returns 1 if attitude, vertical velocity and vertical position will be provided + // Returns 2 if attitude, 3D-velocity, vertical position and relative horizontal position will be provided uint8_t setInhibitGPS(void); // return the horizontal speed limit in m/s set by optical flow limitations