Plane: add new tailsitter bodyframe roll option

This commit is contained in:
Mark Whitehorn 2019-03-16 06:51:05 -06:00 committed by Randy Mackay
parent 4e9b6d1919
commit e0765747e7
3 changed files with 13 additions and 7 deletions

View File

@ -278,7 +278,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: TAILSIT_INPUT
// @DisplayName: Tailsitter input type
// @Description: This controls whether stick input when hovering as a tailsitter follows the conventions for fixed wing hovering or multicopter hovering. When multicopter input is selected the roll stick will roll the aircraft in earth frame and yaw stick will yaw in earth frame. When using fixed wing input the roll and yaw sticks are swapped so that the roll stick controls earth-frame yaw and rudder controls earth-frame roll. When body-frame roll is selected, the yaw stick controls earth-frame yaw rate and the roll stick controls roll in the tailsitter's body frame.
// @Values: 0:MultiCopterInput,1:FixedWingInput,2:BodyFrameRoll
// @Values: 0:MultiCopterInput,1:FixedWingInput,2:BodyFrameRoll_M,3:BodyFrameRoll_P
AP_GROUPINFO("TAILSIT_INPUT", 50, QuadPlane, tailsitter.input_type, TAILSITTER_INPUT_MULTICOPTER),
// @Param: TAILSIT_MASK
@ -738,13 +738,17 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds)
check_attitude_relax();
if (in_vtol_mode() || is_tailsitter()) {
if (tailsitter.input_type == TAILSITTER_INPUT_BF_ROLL) {
if (tailsitter.input_type == TAILSITTER_INPUT_BF_ROLL_M) {
// Angle mode attitude control for pitch and body-frame roll, rate control for yaw.
// this version interprets the first argument as yaw rate and the third as roll 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,
attitude_control->input_euler_rate_yaw_euler_angle_pitch_bf_roll_m(plane.nav_roll_cd,
plane.nav_pitch_cd,
yaw_rate_cds);
} else if (tailsitter.input_type == TAILSITTER_INPUT_BF_ROLL_P) {
attitude_control->input_euler_rate_yaw_euler_angle_pitch_bf_roll_p(plane.nav_roll_cd,
plane.nav_pitch_cd,
yaw_rate_cds);
} else {

View File

@ -414,7 +414,8 @@ private:
enum tailsitter_input {
TAILSITTER_INPUT_MULTICOPTER = 0,
TAILSITTER_INPUT_PLANE = 1,
TAILSITTER_INPUT_BF_ROLL = 2,
TAILSITTER_INPUT_BF_ROLL_M = 2,
TAILSITTER_INPUT_BF_ROLL_P = 3,
};
enum tailsitter_mask {

View File

@ -210,7 +210,8 @@ bool QuadPlane::tailsitter_transition_vtol_complete(void) const
void QuadPlane::tailsitter_check_input(void)
{
if (tailsitter_active() &&
(tailsitter.input_type == TAILSITTER_INPUT_BF_ROLL ||
(tailsitter.input_type == TAILSITTER_INPUT_BF_ROLL_P ||
tailsitter.input_type == TAILSITTER_INPUT_BF_ROLL_M ||
tailsitter.input_type == TAILSITTER_INPUT_PLANE)) {
// the user has asked for body frame controls when tailsitter
// is active. We switch around the control_in value for the