mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Plane: update takeoff course when conditions met
This allows for change of heading before the final takeoff conditions are met thanks to Greg Fletcher for suggesting this
This commit is contained in:
parent
fff777bda2
commit
75ef7c26e1
@ -440,6 +440,11 @@ static bool suppress_throttle(void)
|
||||
if (control_mode==AUTO && takeoff_complete == false && auto_takeoff_check()) {
|
||||
// we're in auto takeoff
|
||||
throttle_suppressed = false;
|
||||
if (hold_course_cd != -1) {
|
||||
// update takeoff course hold, if already initialised
|
||||
hold_course_cd = ahrs.yaw_sensor;
|
||||
gcs_send_text_fmt(PSTR("Holding course %ld"), hold_course_cd);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user