Browse Source

Copter: manual throttle scaling fix

Scaling of bottom half of throttle was changed from THR_MIN ~ 500.
Previously it was from 0 ~ 500.
mission-4.1.18
Randy Mackay 12 years ago committed by rmackay9
parent
commit
df1c0d92bd
  1. 2
      ArduCopter/Attitude.pde

2
ArduCopter/Attitude.pde

@ -853,7 +853,7 @@ static int16_t get_pilot_desired_throttle(int16_t throttle_control) @@ -853,7 +853,7 @@ static int16_t get_pilot_desired_throttle(int16_t throttle_control)
// check throttle is above, below or in the deadband
if (throttle_control < THROTTLE_IN_MIDDLE) {
// below the deadband
throttle_out = (float)throttle_control * (float)g.throttle_mid / 500.0f;
throttle_out = g.throttle_min + ((float)(throttle_control-g.throttle_min))*((float)(g.throttle_mid - g.throttle_min))/((float)(500-g.throttle_min));
}else if(throttle_control > THROTTLE_IN_MIDDLE) {
// above the deadband
throttle_out = g.throttle_mid + ((float)(throttle_control-500))*(float)(1000-g.throttle_mid)/500.0f;

Loading…
Cancel
Save