AP_NavEKF3: fixed inverted function setInhibitGpsVertVelUse()
This commit is contained in:
parent
4019a167a9
commit
2c6593e35e
@ -129,7 +129,7 @@ public:
|
||||
|
||||
// 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
|
||||
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 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