Browse Source

AP_NavEKF: getHeightControlLimit modifies height on success

master
Randy Mackay 10 years ago
parent
commit
b05bdd657d
  1. 4
      libraries/AP_NavEKF/AP_NavEKF.cpp

4
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -5045,10 +5045,10 @@ void NavEKF::detectOptFlowTakeoff(void) @@ -5045,10 +5045,10 @@ void NavEKF::detectOptFlowTakeoff(void)
// this is needed to ensure the vehicle does not fly too high when using optical flow navigation
bool NavEKF::getHeightControlLimit(float &height) const
{
// If are doing optical flow nav, ensure the height above ground is within range finder limits after accounting for vehicle tilt and control errors
height = max(float(_rng.max_distance_cm()) * 0.007f - 1.0f, 1.0f);
// only ask for limiting if we are doing optical flow navigation
if (_fusionModeGPS == 3) {
// If are doing optical flow nav, ensure the height above ground is within range finder limits after accounting for vehicle tilt and control errors
height = max(float(_rng.max_distance_cm()) * 0.007f - 1.0f, 1.0f);
return true;
} else {
return false;

Loading…
Cancel
Save