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: remove dead store of cruise_speed #29174

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
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
14 changes: 5 additions & 9 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4257,19 +4257,15 @@ float QuadPlane::get_land_airspeed(void)
if (qstate == QPOS_APPROACH ||
plane.control_mode == &plane.mode_rtl) {
const float cruise_speed = plane.aparm.airspeed_cruise;
// assume cruise speed, but try to do better:
float approach_speed = cruise_speed;
float tecs_land_airspeed = plane.TECS_controller.get_land_airspeed();
if (is_positive(tecs_land_airspeed)) {
approach_speed = tecs_land_airspeed;
} else {
if (qstate == QPOS_APPROACH) {
// default to half way between min airspeed and cruise
// airspeed when on the approach
approach_speed = 0.5*(cruise_speed+plane.aparm.airspeed_min);
} else {
// otherwise cruise
approach_speed = cruise_speed;
}
} else if (qstate == QPOS_APPROACH) {
// default to half way between min airspeed and cruise
// airspeed when on the approach
approach_speed = 0.5*(cruise_speed+plane.aparm.airspeed_min);
}
const float time_to_pos1 = (plane.auto_state.wp_distance - stopping_distance(sq(approach_speed))) / MAX(approach_speed, 5);
/*
Expand Down
Loading