Browse Source

Copter: constrain throttle before setting deadband

zr-v5.1
Ryan Birmingham 4 years ago committed by Randy Mackay
parent
commit
c2cdb00f85
  1. 10
      ArduCopter/Attitude.cpp

10
ArduCopter/Attitude.cpp

@ -84,17 +84,17 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control) @@ -84,17 +84,17 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control)
}
#endif
float desired_rate = 0.0f;
float mid_stick = get_throttle_mid();
float deadband_top = mid_stick + g.throttle_deadzone;
float deadband_bottom = mid_stick - g.throttle_deadzone;
// ensure a reasonable throttle value
throttle_control = constrain_float(throttle_control,0.0f,1000.0f);
// ensure a reasonable deadzone
g.throttle_deadzone = constrain_int16(g.throttle_deadzone, 0, 400);
float desired_rate = 0.0f;
const float mid_stick = get_throttle_mid();
const float deadband_top = mid_stick + g.throttle_deadzone;
const float deadband_bottom = mid_stick - g.throttle_deadzone;
// check throttle is above, below or in the deadband
if (throttle_control < deadband_bottom) {
// below the deadband

Loading…
Cancel
Save