mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: scale get_pilot_desired_climb_rate() deadzone and output with pilot gain
This commit is contained in:
parent
3ba63d33d5
commit
622ddcf47a
@ -96,8 +96,8 @@ float Sub::get_pilot_desired_climb_rate(float throttle_control)
|
|||||||
|
|
||||||
float desired_rate = 0.0f;
|
float desired_rate = 0.0f;
|
||||||
float mid_stick = channel_throttle->get_control_mid();
|
float mid_stick = channel_throttle->get_control_mid();
|
||||||
float deadband_top = mid_stick + g.throttle_deadzone;
|
float deadband_top = mid_stick + g.throttle_deadzone * gain;
|
||||||
float deadband_bottom = mid_stick - g.throttle_deadzone;
|
float deadband_bottom = mid_stick - g.throttle_deadzone * gain;
|
||||||
|
|
||||||
// ensure a reasonable throttle value
|
// ensure a reasonable throttle value
|
||||||
throttle_control = constrain_float(throttle_control,0.0f,1000.0f);
|
throttle_control = constrain_float(throttle_control,0.0f,1000.0f);
|
||||||
|
@ -271,7 +271,7 @@ const AP_Param::Info Sub::var_info[] = {
|
|||||||
|
|
||||||
// @Param: JS_THR_GAIN
|
// @Param: JS_THR_GAIN
|
||||||
// @DisplayName: Throttle gain scalar
|
// @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
|
// @User: Standard
|
||||||
// @Range: 0.5 4.0
|
// @Range: 0.5 4.0
|
||||||
GSCALAR(throttle_gain, "JS_THR_GAIN", 1.0f),
|
GSCALAR(throttle_gain, "JS_THR_GAIN", 1.0f),
|
||||||
|
Loading…
Reference in New Issue
Block a user