diff --git a/ArduCopter/mode_acro.cpp b/ArduCopter/mode_acro.cpp index 03160ab2a0..c1767407ce 100644 --- a/ArduCopter/mode_acro.cpp +++ b/ArduCopter/mode_acro.cpp @@ -162,7 +162,7 @@ void ModeAcro::get_pilot_desired_angle_rates(float roll_in, float pitch_in, floa } // convert earth-frame level rates to body-frame level rates - attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd() * radians(0.01f), rate_ef_level_cd, rate_bf_level_cd); + attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level_cd, rate_bf_level_cd); // combine earth frame rate corrections with rate requests if (g.acro_trainer == (uint8_t)Trainer::LIMITED) { diff --git a/ArduCopter/mode_acro_heli.cpp b/ArduCopter/mode_acro_heli.cpp index 17dc05bad2..91259ce975 100644 --- a/ArduCopter/mode_acro_heli.cpp +++ b/ArduCopter/mode_acro_heli.cpp @@ -144,7 +144,7 @@ void ModeAcro_Heli::virtual_flybar( float &roll_out, float &pitch_out, float &ya rate_ef_level.z = 0; // convert earth-frame leak rates to body-frame leak rates - attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd()*radians(0.01f), rate_ef_level, rate_bf_level); + attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level, rate_bf_level); // combine earth frame rate corrections with rate requests roll_out += rate_bf_level.x;