Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: fixed usage of rangefinder in landing with RNGFND_LANDING=0 #15710

Merged
merged 1 commit into from
Nov 2, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion ArduPlane/altitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
3 changes: 2 additions & 1 deletion ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down