diff --git a/ArduSub/Attitude.cpp b/ArduSub/Attitude.cpp index 311ecd5662..0c59986d0f 100644 --- a/ArduSub/Attitude.cpp +++ b/ArduSub/Attitude.cpp @@ -94,33 +94,19 @@ float Sub::get_pilot_desired_climb_rate(float throttle_control) return 0.0f; } - 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; - // 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); - // check throttle is above, below or in the deadband - if (throttle_control < deadband_bottom) { - // below the deadband - desired_rate = get_pilot_speed_dn() * (throttle_control-deadband_bottom) / deadband_bottom; - } else if (throttle_control > deadband_top) { - // above the deadband - desired_rate = g.pilot_speed_up * (throttle_control-deadband_top) / (1000.0f-deadband_top); - } else { - // must be in the deadband - desired_rate = 0.0f; + uint16_t dead_zone = channel_throttle->get_dead_zone(); + uint16_t center = (channel_throttle->get_radio_max() + channel_throttle->get_radio_min())/2; + float throttle = throttle_control - center + 1000; + if (abs(throttle) < dead_zone) { + return 0; } - - // desired climb rate for logging - desired_climb_rate = desired_rate; - - return desired_rate; + return throttle; } // get_surface_tracking_climb_rate - hold vehicle at the desired distance above the ground