From 95f3041d25f39f29f70041015509bb78b1c43e6d Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 20 Jun 2012 15:02:00 -0700 Subject: [PATCH] Parameters.h: throttle_min and throttle_max now have defaults from Config.h --- ArduCopter/Parameters.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 780b210dfe..296fb0bd90 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -350,8 +350,8 @@ public: crosstrack_gain (CROSSTRACK_GAIN), auto_land_timeout (AUTO_LAND_TIME * 1000), - throttle_min (0), - throttle_max (1000), + throttle_min (MINIMUM_THROTTLE), + throttle_max (MAXIMUM_THROTTLE), throttle_fs_enabled (THROTTLE_FAILSAFE), throttle_fs_action (THROTTLE_FAILSAFE_ACTION), throttle_fs_value (THROTTLE_FS_VALUE),