Plane: quadplane: limit post VTOL transtion pitch rate on tailsitters in maunal modes

This commit is contained in:
Peter Hall 2021-11-10 02:15:32 +00:00 committed by Andrew Tridgell
parent 67d7ba490f
commit d054ca0426
1 changed files with 2 additions and 0 deletions

View File

@ -64,6 +64,8 @@ void ModeQStabilize::set_tailsitter_roll_pitch(const float roll_input, const flo
// angle max for tailsitter pitch
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