From 46badc05bcd1a64ab0765ba84255f7065e5ffa94 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 12 Jun 2014 11:53:02 +0900 Subject: [PATCH] Copter: guided mode sets desired velocity instead of target velocity --- ArduCopter/control_guided.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/control_guided.pde b/ArduCopter/control_guided.pde index 869935d4dc..9fd7774016 100644 --- a/ArduCopter/control_guided.pde +++ b/ArduCopter/control_guided.pde @@ -84,7 +84,7 @@ static void guided_set_velocity(const Vector3f& velocity) } // set position controller velocity target - pos_control.set_vel_target(velocity); + pos_control.set_desired_velocity(velocity); } // guided_run - runs the guided controller