From 14cb042e89d60ff955f50a0b56ed4ba189cd3011 Mon Sep 17 00:00:00 2001 From: Arjun Vinod Date: Wed, 15 May 2019 11:33:19 -0400 Subject: [PATCH] Rover: use WP_SPEED instead of CRUISE_SPEED to set loiter's maximum speed --- APMrover2/mode_loiter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/mode_loiter.cpp b/APMrover2/mode_loiter.cpp index 0f3eda65f0..4f08867ff9 100644 --- a/APMrover2/mode_loiter.cpp +++ b/APMrover2/mode_loiter.cpp @@ -30,7 +30,7 @@ void ModeLoiter::update() } else { // P controller with hard-coded gain to convert distance to desired speed // To-Do: make gain configurable or calculate from attitude controller's maximum accelearation - _desired_speed = MIN((_distance_to_destination - g2.loit_radius) * 0.5f, g.speed_cruise); + _desired_speed = MIN((_distance_to_destination - g2.loit_radius) * 0.5f, g2.wp_nav.get_default_speed()); // calculate bearing to destination _desired_yaw_cd = rover.current_loc.get_bearing_to(_destination);