Skip to content

Commit

Permalink
FixedwingRateControl: rework VTOL differential thrust saturation
Browse files Browse the repository at this point in the history
Co-authored-by: Silvan Fuhrer <[email protected]>
  • Loading branch information
MaEtUgR and sfuhrer committed Jun 19, 2023
1 parent 53b9e66 commit 69aebe6
Show file tree
Hide file tree
Showing 2 changed files with 39 additions and 16 deletions.
45 changes: 30 additions & 15 deletions src/modules/fw_rate_control/FixedwingRateControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -278,26 +278,41 @@ void FixedwingRateControl::Run()
_rate_control.resetIntegral();
}

// update saturation status from control allocation feedback
control_allocator_status_s control_allocator_status;

if (_control_allocator_status_subs[_vehicle_status.is_vtol ? 1 : 0].update(&control_allocator_status)) {
Vector<bool, 3> saturation_positive;
Vector<bool, 3> saturation_negative;
// Update saturation status from control allocation feedback
// TODO: send the unallocated value directly for better anti-windup
Vector3<bool> diffthr_enabled(
_param_vt_fw_difthr_en.get() & static_cast<int32_t>(VTOLFixedWingDifferentialThrustEnabledBit::ROLL_BIT),
_param_vt_fw_difthr_en.get() & static_cast<int32_t>(VTOLFixedWingDifferentialThrustEnabledBit::PITCH_BIT),
_param_vt_fw_difthr_en.get() & static_cast<int32_t>(VTOLFixedWingDifferentialThrustEnabledBit::YAW_BIT)
);

if (_vehicle_status.is_vtol_tailsitter) {
// Swap roll and yaw
diffthr_enabled.swapRows(0, 2);
}

if (!control_allocator_status.torque_setpoint_achieved) {
for (size_t i = 0; i < 3; i++) {
if (control_allocator_status.unallocated_torque[i] > FLT_EPSILON) {
saturation_positive(i) = true;
// saturation handling for axis controlled by differential thrust (VTOL only)
control_allocator_status_s control_allocator_status;

} else if (control_allocator_status.unallocated_torque[i] < -FLT_EPSILON) {
saturation_negative(i) = true;
}
// Set saturation flags for VTOL differential thrust feature
// If differential thrust is enabled in an axis, assume it's the only torque authority and only update saturation using matrix 0 allocating the motors.
if (_control_allocator_status_subs[0].update(&control_allocator_status)) {
for (size_t i = 0; i < 3; i++) {
if (diffthr_enabled(i)) {
_rate_control.setPositiveSaturationFlag(i, control_allocator_status.unallocated_torque[i] > FLT_EPSILON);
_rate_control.setNegativeSaturationFlag(i, control_allocator_status.unallocated_torque[i] < -FLT_EPSILON);
}
}
}

// TODO: send the unallocated value directly for better anti-windup
_rate_control.setSaturationStatus(saturation_positive, saturation_negative);
// Set saturation flags for control surface controlled axes
if (_control_allocator_status_subs[_vehicle_status.is_vtol ? 1 : 0].update(&control_allocator_status)) {
for (size_t i = 0; i < 3; i++) {
if (!diffthr_enabled(i)) {
_rate_control.setPositiveSaturationFlag(i, control_allocator_status.unallocated_torque[i] > FLT_EPSILON);
_rate_control.setNegativeSaturationFlag(i, control_allocator_status.unallocated_torque[i] < -FLT_EPSILON);
}
}
}

/* bi-linear interpolation over airspeed for actuator trim scheduling */
Expand Down
10 changes: 9 additions & 1 deletion src/modules/fw_rate_control/FixedwingRateControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,13 @@ class FixedwingRateControl final : public ModuleBase<FixedwingRateControl>, publ

bool _in_fw_or_transition_wo_tailsitter_transition{false}; // only run the FW attitude controller in these states

// enum for bitmask of VT_FW_DIFTHR_EN parameter options
enum class VTOLFixedWingDifferentialThrustEnabledBit : int32_t {
YAW_BIT = (1 << 0),
ROLL_BIT = (1 << 1),
PITCH_BIT = (1 << 2),
};

DEFINE_PARAMETERS(
(ParamFloat<px4::params::FW_ACRO_X_MAX>) _param_fw_acro_x_max,
(ParamFloat<px4::params::FW_ACRO_Y_MAX>) _param_fw_acro_y_max,
Expand Down Expand Up @@ -194,7 +201,8 @@ class FixedwingRateControl final : public ModuleBase<FixedwingRateControl>, publ
(ParamFloat<px4::params::TRIM_ROLL>) _param_trim_roll,
(ParamFloat<px4::params::TRIM_YAW>) _param_trim_yaw,

(ParamInt<px4::params::FW_SPOILERS_MAN>) _param_fw_spoilers_man
(ParamInt<px4::params::FW_SPOILERS_MAN>) _param_fw_spoilers_man,
(ParamInt<px4::params::VT_FW_DIFTHR_EN>) _param_vt_fw_difthr_en
)

RateControl _rate_control; ///< class for rate control calculations
Expand Down

0 comments on commit 69aebe6

Please sign in to comment.