AP_NavEKF3: Fix GPS use inhibit interface documentation
This commit is contained in:
parent
c7e1828238
commit
e5e4883c72
@ -874,11 +874,9 @@ bool NavEKF3::resetHeightDatum(void)
|
||||
}
|
||||
|
||||
// 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)
|
||||
// This command must be sent prior to vehicle arming and EKF commencement of GPS usage
|
||||
// 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
|
||||
// Returns 1 if command accepted
|
||||
uint8_t NavEKF3::setInhibitGPS(void)
|
||||
{
|
||||
if (!core) {
|
||||
|
@ -112,11 +112,9 @@ public:
|
||||
bool resetHeightDatum(void);
|
||||
|
||||
// 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)
|
||||
// This command must be sent prior to vehicle arming and EKF commencement of GPS usage
|
||||
// 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
|
||||
// Returns 1 if command accepted
|
||||
uint8_t setInhibitGPS(void);
|
||||
|
||||
// return the horizontal speed limit in m/s set by optical flow sensor limits
|
||||
|
@ -449,20 +449,17 @@ bool NavEKF3_core::checkGyroCalStatus(void)
|
||||
}
|
||||
|
||||
// Commands the EKF to not use GPS.
|
||||
// This command must be sent prior to arming
|
||||
// This command is forgotten by the EKF each time the vehicle disarms
|
||||
// This command must be sent prior to vehicle arming and EKF commencement of GPS usage
|
||||
// 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
|
||||
// Returns 1 if command accepted
|
||||
uint8_t NavEKF3_core::setInhibitGPS(void)
|
||||
{
|
||||
if((PV_AidingMode == AID_ABSOLUTE) && motorsArmed) {
|
||||
if((PV_AidingMode == AID_ABSOLUTE) || motorsArmed) {
|
||||
return 0;
|
||||
} else {
|
||||
gpsInhibit = true;
|
||||
return 1;
|
||||
}
|
||||
// option 2 is not yet implemented as it requires a deeper integration of optical flow and GPS operation
|
||||
}
|
||||
|
||||
// Update the filter status
|
||||
|
@ -125,11 +125,9 @@ public:
|
||||
bool resetHeightDatum(void);
|
||||
|
||||
// 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)
|
||||
// This command must be sent prior to vehicle arming and EKF commencement of GPS usage
|
||||
// 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
|
||||
// Returns 1 if command accepted
|
||||
uint8_t setInhibitGPS(void);
|
||||
|
||||
// return the horizontal speed limit in m/s set by optical flow sensor limits
|
||||
|
Loading…
Reference in New Issue
Block a user