mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_NavEKF2: fixed inverted function setInhibitGpsVertVelUse()
This commit is contained in:
parent
f7db538220
commit
4019a167a9
@ -134,7 +134,7 @@ public:
|
|||||||
|
|
||||||
// Set the argument to true to prevent the EKF using the GPS vertical velocity
|
// Set the argument to true to prevent the EKF using the GPS vertical velocity
|
||||||
// This can be used for situations where GPS velocity errors are causing problems with height accuracy
|
// This can be used for situations where GPS velocity errors are causing problems with height accuracy
|
||||||
void setGpsVertVelUse(const bool varIn) { inhibitGpsVertVelUse = varIn; };
|
void setInhibitGpsVertVelUse(const bool varIn) { inhibitGpsVertVelUse = varIn; };
|
||||||
|
|
||||||
// return the horizontal speed limit in m/s set by optical flow sensor limits
|
// return the horizontal speed limit in m/s set by optical flow sensor limits
|
||||||
// return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow
|
// return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow
|
||||||
|
Loading…
Reference in New Issue
Block a user