mirror of https://github.com/ArduPilot/ardupilot
Plane: zero course error for straight bungee launch
This fixes the behavior where it uses the heading when switched to AUTO instead of at launch causing a turn just after a bungee launch
This commit is contained in:
parent
62b2a2117d
commit
607201a9b1
|
@ -72,6 +72,7 @@ bool Plane::auto_takeoff_check(void)
|
|||
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Triggered AUTO. GPS speed = %.1f", (double)gps.ground_speed());
|
||||
launchTimerStarted = false;
|
||||
last_tkoff_arm_time = 0;
|
||||
steer_state.locked_course_err = 0; // use current heading without any error offset
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue