AP_NavEKF: Improve comments in setInhibitGPS public method

This commit is contained in:
priseborough 2014-11-16 07:03:17 +11:00 committed by Andrew Tridgell
parent 416eaf4633
commit bc2255d6b1
2 changed files with 8 additions and 5 deletions

View File

@ -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;

View File

@ -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