mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduPlane: add tailsitter input type TAILSITTER_INPUT_BF_ROLL
This commit is contained in:
parent
01d6f1d932
commit
4a6b97828f
@ -277,8 +277,8 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
|||||||
|
|
||||||
// @Param: TAILSIT_INPUT
|
// @Param: TAILSIT_INPUT
|
||||||
// @DisplayName: Tailsitter input type
|
// @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.
|
// @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
|
// @Values: 0:MultiCopterInput,1:FixedWingInput,2:BodyFrameRoll
|
||||||
AP_GROUPINFO("TAILSIT_INPUT", 50, QuadPlane, tailsitter.input_type, TAILSITTER_INPUT_MULTICOPTER),
|
AP_GROUPINFO("TAILSIT_INPUT", 50, QuadPlane, tailsitter.input_type, TAILSITTER_INPUT_MULTICOPTER),
|
||||||
|
|
||||||
// @Param: TAILSIT_MASK
|
// @Param: TAILSIT_MASK
|
||||||
@ -738,14 +738,21 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds)
|
|||||||
check_attitude_relax();
|
check_attitude_relax();
|
||||||
|
|
||||||
if (in_vtol_mode() || is_tailsitter()) {
|
if (in_vtol_mode() || is_tailsitter()) {
|
||||||
// use euler angle attitude control
|
if (tailsitter.input_type == TAILSITTER_INPUT_BF_ROLL) {
|
||||||
// this version interprets the first argument as a rate and the third as an angle
|
// Angle mode attitude control for pitch and body-frame roll, rate control for yaw.
|
||||||
// because it is intended to be used with Q_TAILSIT_INPUT=1 where the roll and yaw sticks
|
// this version interprets the first argument as yaw rate and the third as roll angle
|
||||||
// act in the tailsitter's body frame (i.e. roll is MC/earth frame yaw and
|
// because it is intended to be used with Q_TAILSIT_INPUT=1 where the roll and yaw sticks
|
||||||
// yaw is MC/earth frame roll)
|
// act in the tailsitter's body frame (i.e. roll is MC/earth frame yaw and
|
||||||
attitude_control->input_euler_rate_yaw_euler_angle_pitch_bf_roll(plane.nav_roll_cd,
|
// yaw is MC/earth frame roll)
|
||||||
plane.nav_pitch_cd,
|
attitude_control->input_euler_rate_yaw_euler_angle_pitch_bf_roll(plane.nav_roll_cd,
|
||||||
yaw_rate_cds);
|
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 {
|
} else {
|
||||||
// use the fixed wing desired rates
|
// use the fixed wing desired rates
|
||||||
float roll_rate = plane.rollController.get_pid_info().desired;
|
float roll_rate = plane.rollController.get_pid_info().desired;
|
||||||
|
@ -412,6 +412,7 @@ private:
|
|||||||
enum tailsitter_input {
|
enum tailsitter_input {
|
||||||
TAILSITTER_INPUT_MULTICOPTER = 0,
|
TAILSITTER_INPUT_MULTICOPTER = 0,
|
||||||
TAILSITTER_INPUT_PLANE = 1,
|
TAILSITTER_INPUT_PLANE = 1,
|
||||||
|
TAILSITTER_INPUT_BF_ROLL = 2,
|
||||||
};
|
};
|
||||||
|
|
||||||
enum tailsitter_mask {
|
enum tailsitter_mask {
|
||||||
|
@ -210,7 +210,8 @@ bool QuadPlane::tailsitter_transition_vtol_complete(void) const
|
|||||||
void QuadPlane::tailsitter_check_input(void)
|
void QuadPlane::tailsitter_check_input(void)
|
||||||
{
|
{
|
||||||
if (tailsitter_active() &&
|
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
|
// the user has asked for body frame controls when tailsitter
|
||||||
// is active. We switch around the control_in value for the
|
// is active. We switch around the control_in value for the
|
||||||
// channels to do this, as that ensures the value is
|
// channels to do this, as that ensures the value is
|
||||||
|
Loading…
Reference in New Issue
Block a user