Copter: `euler_rate_to_ang_vel` takes Quaternion attitude

This commit is contained in:
Iampete1 2024-02-19 23:47:13 +00:00 committed by Randy Mackay
parent f3c32a7c9e
commit f54f7d7dc6
2 changed files with 2 additions and 2 deletions

View File

@ -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) {

View File

@ -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;