Sub: `euler_rate_to_ang_vel` takes Quaternion attitude

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

View File

@ -249,7 +249,7 @@ void Mode::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int1
}
// 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, 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
if (g.acro_trainer == ACRO_TRAINER_LIMITED) {