Skip to content

Commit

Permalink
Sub: scale get_pilot_desired_climb_rate() deadzone and output with pi…
Browse files Browse the repository at this point in the history
…lot gain
  • Loading branch information
Williangalvani committed Nov 9, 2023
1 parent 3ba63d3 commit 622ddcf
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
4 changes: 2 additions & 2 deletions ArduSub/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down

0 comments on commit 622ddcf

Please sign in to comment.