mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
Plane: init hold_course in do_takeoff
This commit is contained in:
parent
25da4ec0ea
commit
d36ee786e4
@ -329,6 +329,7 @@ void Plane::do_takeoff(const AP_Mission::Mission_Command& cmd)
|
||||
|
||||
// zero locked course
|
||||
steer_state.locked_course_err = 0;
|
||||
steer_state.hold_course_cd = -1;
|
||||
}
|
||||
|
||||
void Plane::do_nav_wp(const AP_Mission::Mission_Command& cmd)
|
||||
|
Loading…
Reference in New Issue
Block a user