mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
ArduPlane: add body-frame yaw mode for tailsitters
This commit is contained in:
parent
872c3df45c
commit
01d6f1d932
@ -739,7 +739,11 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds)
|
||||
|
||||
if (in_vtol_mode() || is_tailsitter()) {
|
||||
// use euler angle attitude control
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
|
||||
// this version interprets the first argument as a rate and the third as an angle
|
||||
// because it is intended to be used with Q_TAILSIT_INPUT=1 where the roll and yaw sticks
|
||||
// act in the tailsitter's body frame (i.e. roll is MC/earth frame yaw and
|
||||
// yaw is MC/earth frame roll)
|
||||
attitude_control->input_euler_rate_yaw_euler_angle_pitch_bf_roll(plane.nav_roll_cd,
|
||||
plane.nav_pitch_cd,
|
||||
yaw_rate_cds);
|
||||
} else {
|
||||
|
Loading…
Reference in New Issue
Block a user