Enable motor controls for tailsitter VTOLs in fixed wing mode (enable Quad Tailsitters) (#20511)

* Enable motor controls for fixed wing mode in tailsitters

This commit enable motor controls in fixed wing mode for tailsitters

This is needed for enabling quad tailsitters

* VTOL: differential thrust in FW: adapt params to be generic for all axes

Until now only suppoted on yaw axis. Not to be supported also on Roll and Pitch.

- VT_FW_DIFTHR_EN: make bitmask for all three axes independently. First bit is Yaw,
sucht that existing meaning of VT_FW_DIFTHR_EN doesn't change.
- VT_FW_DIFTHR_SC: rename to VT_FW_DIFTHR_S_Y and add same params for roll (_R) and
pitch (_P).

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

* Integrate differential control bits to three axis control

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
JaeyoungLim 2022-11-07 15:29:14 +01:00 committed by GitHub
parent 1fc1a81d8f
commit a9542baf3c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
8 changed files with 85 additions and 18 deletions

View File

@ -14,7 +14,7 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=xvert}
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 0
param set-default VT_FW_DIFTHR_EN 1
param set-default VT_FW_DIFTHR_SC 0.3
param set-default VT_FW_DIFTHR_S_Y 0.3
param set-default MPC_MAN_Y_MAX 60
param set-default MC_PITCH_P 5

View File

@ -70,7 +70,7 @@ param set-default MPC_XY_VEL_D_ACC 0.1
param set-default NAV_ACC_RAD 5
param set-default VT_FW_DIFTHR_EN 1
param set-default VT_FW_DIFTHR_SC 0.5
param set-default VT_FW_DIFTHR_S_Y 0.5
param set-default VT_F_TRANS_DUR 1.5
param set-default VT_F_TRANS_THR 0.7
param set-default VT_TYPE 0

View File

@ -22,7 +22,7 @@ param set-default VT_ELEV_MC_LOCK 0
param set-default VT_MOT_COUNT 2
param set-default VT_TYPE 0
param set-default VT_FW_DIFTHR_EN 1
param set-default VT_FW_DIFTHR_SC 0.3
param set-default VT_FW_DIFTHR_S_Y 0.3
param set-default MPC_MAN_Y_MAX 60
param set-default MC_PITCH_P 5

View File

@ -250,5 +250,14 @@ bool param_modify_on_import(bson_node_t node)
}
}
// 2022-07-18: translate VT_FW_DIFTHR_SC->VT_FW_DIFTHR_S_Y
{
if (strcmp("VT_FW_DIFTHR_SC", node->name) == 0) {
strcpy(node->name, "VT_FW_DIFTHR_S_Y");
PX4_INFO("copying %s -> %s", "VT_FW_DIFTHR_SC", "VT_FW_DIFTHR_S_Y");
return true;
}
}
return false;
}

View File

@ -343,9 +343,22 @@ void Tailsitter::fill_actuator_outputs()
_thrust_setpoint_0->xyz[2] = -fw_in[actuator_controls_s::INDEX_THROTTLE];
/* allow differential thrust if enabled */
if (_param_vt_fw_difthr_en.get()) {
mc_out[actuator_controls_s::INDEX_ROLL] = fw_in[actuator_controls_s::INDEX_YAW] * _param_vt_fw_difthr_sc.get() ;
_torque_setpoint_0->xyz[0] = fw_in[actuator_controls_s::INDEX_YAW] * _param_vt_fw_difthr_sc.get() ;
if (_param_vt_fw_difthr_en.get() & static_cast<int32_t>(VtFwDifthrEnBits::YAW_BIT)) {
float yaw_control = fw_in[actuator_controls_s::INDEX_YAW] * _param_vt_fw_difthr_s_y.get();
mc_out[actuator_controls_s::INDEX_ROLL] = yaw_control;
_torque_setpoint_0->xyz[0] = yaw_control;
}
if (_param_vt_fw_difthr_en.get() & static_cast<int32_t>(VtFwDifthrEnBits::PITCH_BIT)) {
float pitch_control = fw_in[actuator_controls_s::INDEX_PITCH] * _param_vt_fw_difthr_s_p.get();
mc_out[actuator_controls_s::INDEX_PITCH] = pitch_control;
_torque_setpoint_0->xyz[1] = pitch_control;
}
if (_param_vt_fw_difthr_en.get() & static_cast<int32_t>(VtFwDifthrEnBits::ROLL_BIT)) {
float roll_control = -fw_in[actuator_controls_s::INDEX_ROLL] * _param_vt_fw_difthr_s_r.get();
mc_out[actuator_controls_s::INDEX_YAW] = roll_control;
_torque_setpoint_0->xyz[2] = roll_control;
}
} else {

View File

@ -481,9 +481,9 @@ void Tiltrotor::fill_actuator_outputs()
_thrust_setpoint_0->xyz[2] = fw_in[actuator_controls_s::INDEX_THROTTLE];
/* allow differential thrust if enabled */
if (_param_vt_fw_difthr_en.get()) {
mc_out[actuator_controls_s::INDEX_ROLL] = fw_in[actuator_controls_s::INDEX_YAW] * _param_vt_fw_difthr_sc.get() ;
_torque_setpoint_0->xyz[2] = fw_in[actuator_controls_s::INDEX_YAW] * _param_vt_fw_difthr_sc.get() ;
if (_param_vt_fw_difthr_en.get() & static_cast<int32_t>(VtFwDifthrEnBits::YAW_BIT)) {
mc_out[actuator_controls_s::INDEX_ROLL] = fw_in[actuator_controls_s::INDEX_YAW] * _param_vt_fw_difthr_s_y.get() ;
_torque_setpoint_0->xyz[2] = fw_in[actuator_controls_s::INDEX_YAW] * _param_vt_fw_difthr_s_y.get() ;
}
} else {

View File

@ -254,27 +254,63 @@ PARAM_DEFINE_FLOAT(VT_F_TR_OL_TM, 6.0f);
/**
* Differential thrust in forwards flight.
*
* Set to 1 to enable differential thrust in fixed-wing flight.
* Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode.
* The effectiveness of differential thrust around the corresponding axis can be
* tuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y.
*
* @min 0
* @max 1
* @decimal 0
* @max 7
* @bit 0 Yaw
* @bit 1 Roll
* @bit 2 Pitch
* @group VTOL Attitude Control
*/
PARAM_DEFINE_INT32(VT_FW_DIFTHR_EN, 0);
/**
* Differential thrust scaling factor
* Roll differential thrust factor in forward flight
*
* This factor specifies how the yaw input gets mapped to differential thrust in forwards flight.
* Maps the roll control output in forward flight to the actuator differential thrust output.
*
* Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.
*
* @min 0.0
* @max 1.0
* @max 2.0
* @decimal 2
* @increment 0.1
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_FW_DIFTHR_SC, 0.1f);
PARAM_DEFINE_FLOAT(VT_FW_DIFTHR_S_R, 1.f);
/**
* Pitch differential thrust factor in forward flight
*
* Maps the pitch control output in forward flight to the actuator differential thrust output.
*
* Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.
*
* @min 0.0
* @max 2.0
* @decimal 2
* @increment 0.1
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_FW_DIFTHR_S_P, 1.f);
/**
* Yaw differential thrust factor in forward flight
*
* Maps the yaw control output in forward flight to the actuator differential thrust output.
*
* Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.
*
* @min 0.0
* @max 2.0
* @decimal 2
* @increment 0.1
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_FW_DIFTHR_S_Y, 0.1f);
/**
* Backtransition deceleration setpoint to pitch feedforward gain.

View File

@ -77,6 +77,13 @@ enum VtolForwardActuationMode {
ENABLE_ABOVE_MPC_LAND_ALT2_WITHOUT_LAND
};
// enum for bitmask of VT_FW_DIFTHR_EN parameter options
enum class VtFwDifthrEnBits : int32_t {
YAW_BIT = (1 << 0),
ROLL_BIT = (1 << 1),
PITCH_BIT = (1 << 2),
};
class VtolAttitudeControl;
class VtolType : public ModuleParams
@ -239,8 +246,10 @@ protected:
(ParamBool<px4::params::FW_ARSP_MODE>) _param_fw_arsp_mode,
(ParamFloat<px4::params::VT_TRANS_TIMEOUT>) _param_vt_trans_timeout,
(ParamFloat<px4::params::MPC_XY_CRUISE>) _param_mpc_xy_cruise,
(ParamBool<px4::params::VT_FW_DIFTHR_EN>) _param_vt_fw_difthr_en,
(ParamFloat<px4::params::VT_FW_DIFTHR_SC>) _param_vt_fw_difthr_sc,
(ParamInt<px4::params::VT_FW_DIFTHR_EN>) _param_vt_fw_difthr_en,
(ParamFloat<px4::params::VT_FW_DIFTHR_S_Y>) _param_vt_fw_difthr_s_y,
(ParamFloat<px4::params::VT_FW_DIFTHR_S_P>) _param_vt_fw_difthr_s_p,
(ParamFloat<px4::params::VT_FW_DIFTHR_S_R>) _param_vt_fw_difthr_s_r,
(ParamFloat<px4::params::VT_B_DEC_FF>) _param_vt_b_dec_ff,
(ParamFloat<px4::params::VT_B_DEC_I>) _param_vt_b_dec_i,
(ParamFloat<px4::params::VT_B_DEC_MSS>) _param_vt_b_dec_mss,