Copter: bug fix for control_acro throttle

This commit is contained in:
Randy Mackay 2014-01-31 09:55:00 +09:00 committed by Andrew Tridgell
parent 164bd10ef0
commit c73c9f03a5

View File

@ -17,6 +17,7 @@ static bool acro_init(bool ignore_checks)
static void acro_run()
{
int16_t target_roll, target_pitch, target_yaw;
int16_t pilot_throttle_scaled;
// if motors not running reset angle targets
if(!motors.armed() || g.rc_3.control_in <= 0) {
@ -28,7 +29,14 @@ static void acro_run()
// convert the input to the desired body frame rate
get_pilot_desired_angle_rates(g.rc_1.control_in, g.rc_2.control_in, g.rc_4.control_in, target_roll, target_pitch, target_yaw);
// get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_throttle(g.rc_3.control_in);
// run attitude controller
attitude_control.ratebf_rpy(target_roll, target_pitch, target_yaw);
// output pilot's throttle without angle boost
attitude_control.set_throttle_out(pilot_throttle_scaled, false);
}