From 1b52ee211a4b44c04af5091593eb84f2e8ab16db Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Thu, 9 May 2013 21:44:46 +0900 Subject: [PATCH] Copter: bug fix for RTL yaw control Nose was only pointing home if your initial altitude was above the RTL_ALT --- ArduCopter/commands_logic.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 9389d9b11..74c0ab88d 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -536,8 +536,8 @@ static bool verify_RTL() // Set wp navigation target to above home wp_nav.set_destination(Vector3f(0,0,get_RTL_alt())); - // set yaw mode - set_yaw_mode(YAW_HOLD); + // point nose towards home (maybe) + set_yaw_mode(get_wp_yaw_mode(true)); // advance to next rtl state rtl_state = RTL_STATE_RETURNING_HOME; -- GitLab