From 88b2f62e2f9e5447fdee20c57e076d061beb19f8 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 19 Jul 2017 17:05:01 +0900 Subject: [PATCH] Rover: mode rtl loses duplicate calls to calc_lateral_acceleration Also no need to call calc_nav_steer no need to set throttle before entering hold --- APMrover2/mode_rtl.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/APMrover2/mode_rtl.cpp b/APMrover2/mode_rtl.cpp index d0f94c78c8..de77c08559 100644 --- a/APMrover2/mode_rtl.cpp +++ b/APMrover2/mode_rtl.cpp @@ -23,10 +23,6 @@ void ModeRTL::update_navigation() { // no loitering around the wp with the rover, goes direct to the wp position if (rover.verify_RTL()) { - g2.motors.set_throttle(g.throttle_min.get()); rover.set_mode(rover.mode_hold); - } else { - calc_lateral_acceleration(); - calc_nav_steer(); } }