mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_NavEKF: Improve comments in setInhibitGPS public method
This commit is contained in:
parent
416eaf4633
commit
bc2255d6b1
@ -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 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)
|
// 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)
|
uint8_t NavEKF::setInhibitGPS(void)
|
||||||
{
|
{
|
||||||
// Ignore request if not in in static mode (when armed)
|
|
||||||
if(!staticMode) {
|
if(!staticMode) {
|
||||||
return 0;
|
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()) {
|
if (useOptFlow()) {
|
||||||
gpsInhibitMode = 2;
|
gpsInhibitMode = 2;
|
||||||
return 2;
|
return 2;
|
||||||
|
@ -114,9 +114,12 @@ public:
|
|||||||
// reset body axis gyro bias estimates
|
// reset body axis gyro bias estimates
|
||||||
void resetGyroBias(void);
|
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 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)
|
// 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);
|
uint8_t setInhibitGPS(void);
|
||||||
|
|
||||||
// return the horizontal speed limit in m/s set by optical flow limitations
|
// return the horizontal speed limit in m/s set by optical flow limitations
|
||||||
|
Loading…
Reference in New Issue
Block a user