mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed usage of rangefinder in landing with RNGFND_LANDING=0
this fixes two places where rangefinder can affect landing when RNGFND_LANDING=0
This commit is contained in:
parent
c192efea0a
commit
e5d580412e
|
@ -702,7 +702,9 @@ void Plane::rangefinder_height_update(void)
|
|||
if (now - rangefinder_state.last_correction_time_ms > 5000) {
|
||||
rangefinder_state.correction = correction;
|
||||
rangefinder_state.initial_correction = correction;
|
||||
landing.set_initial_slope();
|
||||
if (g.rangefinder_landing) {
|
||||
landing.set_initial_slope();
|
||||
}
|
||||
rangefinder_state.last_correction_time_ms = now;
|
||||
} else {
|
||||
rangefinder_state.correction = 0.8f*rangefinder_state.correction + 0.2f*correction;
|
||||
|
|
|
@ -233,7 +233,8 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
|
|||
// ground
|
||||
height -= auto_state.terrain_correction;
|
||||
return landing.verify_land(prev_WP_loc, next_WP_loc, current_loc,
|
||||
height, auto_state.sink_rate, auto_state.wp_proportion, auto_state.last_flying_ms, arming.is_armed(), is_flying(), rangefinder_state.in_range);
|
||||
height, auto_state.sink_rate, auto_state.wp_proportion, auto_state.last_flying_ms, arming.is_armed(), is_flying(),
|
||||
g.rangefinder_landing && rangefinder_state.in_range);
|
||||
}
|
||||
|
||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||
|
|
Loading…
Reference in New Issue