From 9aeda9f702126a9d85a48ff8b62e6a2905675086 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Sun, 13 Nov 2011 08:24:56 +0800 Subject: [PATCH] fix loiter radius --- ArduCopter/Parameters.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index eab4008393..098a3685bf 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -322,7 +322,7 @@ public: command_index (0, k_param_command_index, PSTR("WP_INDEX")), command_must_index (0, k_param_command_must_index, PSTR("WP_MUST_INDEX")), waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")), - loiter_radius (LOITER_RADIUS * 100, k_param_loiter_radius, PSTR("WP_LOITER_RAD")), + loiter_radius (LOITER_RADIUS, k_param_loiter_radius, PSTR("WP_LOITER_RAD")), waypoint_speed_max (WAYPOINT_SPEED_MAX, k_param_waypoint_speed_max, PSTR("WP_SPEED_MAX")), throttle_min (0, k_param_throttle_min, PSTR("THR_MIN")),