Copter: get_pilot_desired_climb_rate accepts control_in as 0 to 1000

Previously the input was expected to be throttle_min (i.e. 130) to 1000
This commit is contained in:
Leonard Hall 2016-01-05 20:04:19 +09:00 committed by Randy Mackay
parent 20debc962a
commit 7bcdc76655

View File

@ -161,8 +161,7 @@ float Copter::get_pilot_desired_throttle(int16_t throttle_control)
return throttle_out;
}
// get_pilot_desired_climb_rate - transform pilot's throttle input to
// climb rate in cm/s. we use radio_in instead of control_in to get the full range
// get_pilot_desired_climb_rate - transform pilot's throttle input to climb rate in cm/s
// without any deadzone at the bottom
float Copter::get_pilot_desired_climb_rate(float throttle_control)
{
@ -177,7 +176,7 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control)
float deadband_bottom = mid_stick - g.throttle_deadzone;
// ensure a reasonable throttle value
throttle_control = constrain_float(throttle_control,g.throttle_min,1000.0f);
throttle_control = constrain_float(throttle_control,0.0f,1000.0f);
// ensure a reasonable deadzone
g.throttle_deadzone = constrain_int16(g.throttle_deadzone, 0, 400);
@ -185,7 +184,7 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control)
// check throttle is above, below or in the deadband
if (throttle_control < deadband_bottom) {
// below the deadband
desired_rate = g.pilot_velocity_z_max * (throttle_control-deadband_bottom) / (deadband_bottom-g.throttle_min);
desired_rate = g.pilot_velocity_z_max * (throttle_control-deadband_bottom) / deadband_bottom;
}else if (throttle_control > deadband_top) {
// above the deadband
desired_rate = g.pilot_velocity_z_max * (throttle_control-deadband_top) / (1000.0f-deadband_top);