diff --git a/ArduSub/Attitude.cpp b/ArduSub/Attitude.cpp index 424f853939..408d9bfa6b 100644 --- a/ArduSub/Attitude.cpp +++ b/ArduSub/Attitude.cpp @@ -96,8 +96,8 @@ float Sub::get_pilot_desired_climb_rate(float throttle_control) float desired_rate = 0.0f; float mid_stick = channel_throttle->get_control_mid(); - float deadband_top = mid_stick + g.throttle_deadzone; - float deadband_bottom = mid_stick - g.throttle_deadzone; + float deadband_top = mid_stick + g.throttle_deadzone * gain; + float deadband_bottom = mid_stick - g.throttle_deadzone * gain; // ensure a reasonable throttle value throttle_control = constrain_float(throttle_control,0.0f,1000.0f); diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index e7162c5ebc..73ce3dbcb0 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -271,7 +271,7 @@ const AP_Param::Info Sub::var_info[] = { // @Param: JS_THR_GAIN // @DisplayName: Throttle gain scalar - // @Description: Scalar for gain on the throttle channel + // @Description: Scalar for gain on the throttle channel. Gets scaled with the current JS gain // @User: Standard // @Range: 0.5 4.0 GSCALAR(throttle_gain, "JS_THR_GAIN", 1.0f),