mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: prevent a bad glide slope when first entering auto
we need to ensure that prev_WP_loc is not used as it could be completely different from current_loc. As a precuation, this also sets up next_WP_loc so that when the set_next_WP() is first called that prev_WP_loc is set to current_loc
This commit is contained in:
parent
5fe0d2c1b2
commit
69b5f352f6
@ -256,8 +256,8 @@ static void setup_glide_slope(void)
|
||||
// is basically to prevent situations where we try to slowly
|
||||
// gain height at low altitudes, potentially hitting
|
||||
// obstacles.
|
||||
if (relative_altitude() > 40 || next_WP_loc.alt < prev_WP_loc.alt) {
|
||||
offset_altitude_cm = next_WP_loc.alt - prev_WP_loc.alt;
|
||||
if (relative_altitude() > 40 || next_WP_loc.alt < current_loc.alt) {
|
||||
offset_altitude_cm = next_WP_loc.alt - current_loc.alt;
|
||||
} else {
|
||||
offset_altitude_cm = 0;
|
||||
}
|
||||
|
@ -335,7 +335,7 @@ static void set_mode(enum FlightMode mode)
|
||||
|
||||
case AUTO:
|
||||
auto_throttle_mode = true;
|
||||
prev_WP_loc = current_loc;
|
||||
next_WP_loc = prev_WP_loc = current_loc;
|
||||
// start or resume the mission, based on MIS_AUTORESET
|
||||
mission.start_or_resume();
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user