diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 98bf53b732..04fecedd56 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -24,6 +24,9 @@ //#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space #define AUTOTUNE DISABLED // disable the auto tune functionality to save 7k of flash +// redefine size of throttle deadband in pwm (0 ~ 1000) +//#define THROTTLE_IN_DEADBAND 100 + //#define HIL_MODE HIL_MODE_SENSORS // build for hardware-in-the-loop simulation // User Hooks : For User Developed code that you wish to run diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 74f70ea9ab..2b8d685c19 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -1090,7 +1090,6 @@ static int16_t get_pilot_desired_throttle(int16_t throttle_control) // get_pilot_desired_climb_rate - transform pilot's throttle input to // climb rate in cm/s. we use radio_in instead of control_in to get the full range // without any deadzone at the bottom -#define THROTTLE_IN_DEADBAND 100 // the throttle input channel's deadband in PWM #define THROTTLE_IN_DEADBAND_TOP (THROTTLE_IN_MIDDLE+THROTTLE_IN_DEADBAND) // top of the deadband #define THROTTLE_IN_DEADBAND_BOTTOM (THROTTLE_IN_MIDDLE-THROTTLE_IN_DEADBAND) // bottom of the deadband static int16_t get_pilot_desired_climb_rate(int16_t throttle_control) diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 2191534707..0eb105b19a 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -245,7 +245,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @Range: 0 300 // @Increment: 1 // @User: Standard - GSCALAR(throttle_min, "THR_MIN", MINIMUM_THROTTLE), + GSCALAR(throttle_min, "THR_MIN", THR_MIN_DEFAULT), // @Param: THR_MAX // @DisplayName: Maximum Throttle @@ -254,7 +254,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @Range: 0 1000 // @Increment: 1 // @User: Standard - GSCALAR(throttle_max, "THR_MAX", MAXIMUM_THROTTLE), + GSCALAR(throttle_max, "THR_MAX", THR_MAX_DEFAULT), // @Param: FS_THR_ENABLE // @DisplayName: Throttle Failsafe Enable @@ -286,7 +286,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: Standard // @Range: 300 700 // @Increment: 1 - GSCALAR(throttle_mid, "THR_MID", THR_MID), + GSCALAR(throttle_mid, "THR_MID", THR_MID_DEFAULT), // @Param: FLTMODE1 // @DisplayName: Flight Mode 1 diff --git a/ArduCopter/config.h b/ArduCopter/config.h index b8ad3822c1..c7ac6d3e95 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -502,14 +502,6 @@ # define FS_THR_VALUE_DEFAULT 975 #endif - -#ifndef MINIMUM_THROTTLE - # define MINIMUM_THROTTLE 130 -#endif -#ifndef MAXIMUM_THROTTLE - # define MAXIMUM_THROTTLE 1000 -#endif - #ifndef LAND_SPEED # define LAND_SPEED 50 // the descent speed for the final stage of landing in cm/s #endif @@ -921,8 +913,19 @@ # define THROTTLE_CRUISE 450 // default estimate of throttle required for vehicle to maintain a hover #endif -#ifndef THR_MID - # define THR_MID 500 // Throttle output (0 ~ 1000) when throttle stick is in mid position +#ifndef THR_MID_DEFAULT + # define THR_MID_DEFAULT 500 // Throttle output (0 ~ 1000) when throttle stick is in mid position +#endif + +#ifndef THR_MIN_DEFAULT + # define THR_MIN_DEFAULT 130 // minimum throttle sent to the motors when armed and pilot throttle above zero +#endif +#ifndef THR_MAX_DEFAULT + # define THR_MAX_DEFAULT 1000 // maximum throttle sent to the motors +#endif + +#ifndef THROTTLE_IN_DEADBAND +# define THROTTLE_IN_DEADBAND 100 // the throttle input channel's deadband in PWM #endif #ifndef ALT_HOLD_TAKEOFF_JUMP diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index 53b8b95c1f..4e2a2584d2 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -67,7 +67,7 @@ static void init_rc_out() g.rc_3.set_range_out(0,1000); // full throttle means to enter ESC calibration - if(g.rc_3.control_in >= (MAXIMUM_THROTTLE - 50)) { + if(g.rc_3.control_in >= (g.throttle_max - 50)) { if(g.esc_calibrate == 0) { // we will enter esc_calibrate mode on next reboot g.esc_calibrate.set_and_save(1); @@ -130,11 +130,6 @@ static void read_radio() g.rc_6.set_pwm(periods[5]); g.rc_7.set_pwm(periods[6]); g.rc_8.set_pwm(periods[7]); - -#if FRAME_CONFIG != HELI_FRAME - // limit our input to 800 so we can still pitch and roll - g.rc_3.control_in = min(g.rc_3.control_in, MAXIMUM_THROTTLE); -#endif }else{ uint32_t elapsed = millis() - last_update; // turn on throttle failsafe if no update from ppm encoder for 2 seconds