From 11918869a53a8ca72bc5ce8bd59e280bf76135e9 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 7 May 2014 15:03:00 +0900 Subject: [PATCH] Copter: RTL calls wp_and_spline_init --- ArduCopter/control_rtl.pde | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/control_rtl.pde b/ArduCopter/control_rtl.pde index bb9e8af0ee..1ec6a0c954 100644 --- a/ArduCopter/control_rtl.pde +++ b/ArduCopter/control_rtl.pde @@ -78,6 +78,9 @@ static void rtl_climb_start() rtl_state = InitialClimb; rtl_state_complete = false; + // initialise waypoint and spline controller + wp_nav.wp_and_spline_init(); + // get horizontal stopping point Vector3f destination; wp_nav.get_wp_stopping_point_xy(destination); @@ -90,7 +93,9 @@ static void rtl_climb_start() destination.z = get_RTL_alt(); #endif + // set the destination wp_nav.set_wp_destination(destination); + wp_nav.set_fast_waypoint(true); // hold current yaw during initial climb set_auto_yaw_mode(AUTO_YAW_HOLD);