mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: quadplane: limit post VTOL transtion pitch rate on tailsitters in maunal modes
This commit is contained in:
parent
67d7ba490f
commit
d054ca0426
@ -64,6 +64,8 @@ void ModeQStabilize::set_tailsitter_roll_pitch(const float roll_input, const flo
|
|||||||
|
|
||||||
// angle max for tailsitter pitch
|
// angle max for tailsitter pitch
|
||||||
plane.nav_pitch_cd = pitch_input * plane.quadplane.aparm.angle_max;
|
plane.nav_pitch_cd = pitch_input * plane.quadplane.aparm.angle_max;
|
||||||
|
|
||||||
|
plane.quadplane.transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd);
|
||||||
}
|
}
|
||||||
|
|
||||||
// set the desired roll and pitch for normal quadplanes, also limited by forward flight limtis
|
// set the desired roll and pitch for normal quadplanes, also limited by forward flight limtis
|
||||||
|
Loading…
Reference in New Issue
Block a user