Plane: rotate Qassist desired rates correctly

This commit is contained in:
Iampete1 2022-06-16 23:41:33 +01:00 committed by Andrew Tridgell
parent 0027660f3f
commit f2a162b963
1 changed files with 8 additions and 8 deletions

View File

@ -885,14 +885,14 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds)
}
} else {
// use the fixed wing desired rates
float roll_rate = plane.rollController.get_pid_info().target;
float pitch_rate = plane.pitchController.get_pid_info().target;
if (tailsitter.enabled()) {
// tailsitter roll and yaw swapped due to change in reference frame
attitude_control->input_rate_bf_roll_pitch_yaw_2(yaw_rate_cds,pitch_rate*100.0f, -roll_rate*100.0f);
} else {
attitude_control->input_rate_bf_roll_pitch_yaw_2(roll_rate*100.0f, pitch_rate*100.0f, yaw_rate_cds);
}
Vector3f bf_input_cd { plane.rollController.get_pid_info().target * 100.0f,
plane.pitchController.get_pid_info().target * 100.0f,
yaw_rate_cds };
// rotate into multicopter attitude refence frame
ahrs_view->rotate(bf_input_cd);
attitude_control->input_rate_bf_roll_pitch_yaw_2(bf_input_cd.x, bf_input_cd.y, bf_input_cd.z);
}
}