From 4a6b97828fbd265a9f2cc9d000e1c2855cbf78e7 Mon Sep 17 00:00:00 2001 From: Mark Whitehorn Date: Sun, 3 Mar 2019 10:54:23 -0700 Subject: [PATCH] ArduPlane: add tailsitter input type TAILSITTER_INPUT_BF_ROLL --- ArduPlane/quadplane.cpp | 27 +++++++++++++++++---------- ArduPlane/quadplane.h | 1 + ArduPlane/tailsitter.cpp | 3 ++- 3 files changed, 20 insertions(+), 11 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index c5b43b47d1..82de93d1de 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -277,8 +277,8 @@ 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 will control the aircraft in body frame. - // @Values: 0:MultiCopterInput,1:FixedWingInput + // @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 AP_GROUPINFO("TAILSIT_INPUT", 50, QuadPlane, tailsitter.input_type, TAILSITTER_INPUT_MULTICOPTER), // @Param: TAILSIT_MASK @@ -738,14 +738,21 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds) check_attitude_relax(); if (in_vtol_mode() || is_tailsitter()) { - // use euler angle attitude control - // 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); + if (tailsitter.input_type == TAILSITTER_INPUT_BF_ROLL) { + // 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, + plane.nav_pitch_cd, + yaw_rate_cds); + } else { + // use euler angle attitude control + attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, + plane.nav_pitch_cd, + yaw_rate_cds); + } } else { // use the fixed wing desired rates float roll_rate = plane.rollController.get_pid_info().desired; diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 7bf3137159..1f1711f98b 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -412,6 +412,7 @@ private: enum tailsitter_input { TAILSITTER_INPUT_MULTICOPTER = 0, TAILSITTER_INPUT_PLANE = 1, + TAILSITTER_INPUT_BF_ROLL = 2, }; enum tailsitter_mask { diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 7543bfed6b..d69ff3c90c 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -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_PLANE) { + (tailsitter.input_type == TAILSITTER_INPUT_BF_ROLL || + 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 // channels to do this, as that ensures the value is