From 8ef60f2d75da9164efcb3c3e1039a90182aad5b3 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 20 Jun 2012 14:58:34 -0700 Subject: [PATCH 1/4] Added throttle_min as a user definable param --- ArduCopter/ArduCopter.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 3a94096c48..c1a0e0bdad 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1642,7 +1642,7 @@ void update_throttle_mode(void) throttle_avg = g.throttle_cruise; } // calc average throttle - if ((g.rc_3.control_in > MINIMUM_THROTTLE) && abs(climb_rate) < 60){ + if ((g.rc_3.control_in > g.throttle_min) && abs(climb_rate) < 60){ throttle_avg = throttle_avg * .98 + (float)g.rc_3.control_in * .02; g.throttle_cruise = throttle_avg; } @@ -2054,9 +2054,9 @@ static void update_altitude_est() static void adjust_altitude() { - if(g.rc_3.control_in <= (MINIMUM_THROTTLE + THROTTLE_ADJUST)){ + if(g.rc_3.control_in <= (g.throttle_min + THROTTLE_ADJUST)){ // we remove 0 to 100 PWM from hover - manual_boost = (g.rc_3.control_in - MINIMUM_THROTTLE) - THROTTLE_ADJUST; + manual_boost = (g.rc_3.control_in - g.throttle_min) - THROTTLE_ADJUST; manual_boost = max(-THROTTLE_ADJUST, manual_boost); }else if (g.rc_3.control_in >= (MAXIMUM_THROTTLE - THROTTLE_ADJUST)){ From ef847eecbbaa549952ef88cfb080fb18eabcf9b9 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 20 Jun 2012 15:00:05 -0700 Subject: [PATCH 2/4] changed define to param for throttle_min --- ArduCopter/test.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index 0dc39df279..f2a76d6d68 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -189,7 +189,7 @@ static int8_t { print_hit_enter(); delay(1000); - int16_t temp = MINIMUM_THROTTLE; + int16_t temp = g.throttle_min; while(1){ delay(20); From b8016dfe48000de412ba579f5edb994ddca676ab Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 20 Jun 2012 15:00:53 -0700 Subject: [PATCH 3/4] changed define to a param for throttle_min and throttle_max --- ArduCopter/radio.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index a3c0fbbc2a..571e5045e3 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -26,7 +26,7 @@ static void init_rc_in() // we do not want to limit the movment of the heli's swash plate g.rc_3.set_range(0, 1000); #else - g.rc_3.set_range(MINIMUM_THROTTLE, MAXIMUM_THROTTLE); + g.rc_3.set_range(g.throttle_min, g.throttle_max); #endif g.rc_4.set_angle(4500); @@ -54,8 +54,8 @@ static void init_rc_out() #endif motors.set_frame_orientation(g.frame_orientation); motors.Init(); // motor initialisation - motors.set_min_throttle(MINIMUM_THROTTLE); - motors.set_max_throttle(MAXIMUM_THROTTLE); + motors.set_min_throttle(g.throttle_min); + motors.set_max_throttle(g.throttle_max); // this is the camera pitch5 and roll6 APM_RC.OutputCh(CH_CAM_PITCH, 1500); From 95f3041d25f39f29f70041015509bb78b1c43e6d Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 20 Jun 2012 15:02:00 -0700 Subject: [PATCH 4/4] 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),