mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
APM: reload airspeed and throttle after landing
this allows for restarting a mission after landing with reasonable airspeed values
This commit is contained in:
parent
47be6d8ad1
commit
2d7fcbd14b
@ -334,6 +334,12 @@ static bool verify_land()
|
|||||||
hold_course = ahrs.yaw_sensor;
|
hold_course = ahrs.yaw_sensor;
|
||||||
gcs_send_text_fmt(PSTR("Holding course %ld"), hold_course);
|
gcs_send_text_fmt(PSTR("Holding course %ld"), hold_course);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// reload any airspeed or groundspeed parameters that may have
|
||||||
|
// been set for landing
|
||||||
|
g.airspeed_cruise_cm.load();
|
||||||
|
g.min_gndspeed_cm.load();
|
||||||
|
g.throttle_cruise.load();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hold_course != -1) {
|
if (hold_course != -1) {
|
||||||
|
Loading…
Reference in New Issue
Block a user