diff --git a/src/modules/control_allocator/ControlAllocator.cpp b/src/modules/control_allocator/ControlAllocator.cpp index aa835747f2cc..28717b554795 100644 --- a/src/modules/control_allocator/ControlAllocator.cpp +++ b/src/modules/control_allocator/ControlAllocator.cpp @@ -478,16 +478,7 @@ ControlAllocator::Run() // Do allocation _control_allocation[i]->allocate(); - bool is_tiltrotor = _effectiveness_source_id == EffectivenessSource::TILTROTOR_VTOL; - - if (_preflight_check_running && is_tiltrotor) { - float preflight_check_tilt_sp = preflight_check_get_tilt_control(); - _actuator_effectiveness->setBypassTiltrotorControls(true, preflight_check_tilt_sp, 0.0f); - - } else { - _actuator_effectiveness->setBypassTiltrotorControls(false, 0.0f, 0.0f); - - } + preflight_check_handle_tilt_control(); _actuator_effectiveness->allocateAuxilaryControls(dt, i, _control_allocation[i]->_actuator_sp); //flaps and spoilers _actuator_effectiveness->updateSetpoint(c[i], i, _control_allocation[i]->_actuator_sp, @@ -522,6 +513,8 @@ ControlAllocator::Run() void ControlAllocator::preflight_check_start(vehicle_command_s &cmd) { + // If one is running, abort it. Depending on the use case we may prefer + // to instead "silently" overwrite the value. if (_preflight_check_running) { preflight_check_abort(); } @@ -563,7 +556,6 @@ void ControlAllocator::preflight_check_abort() } - void ControlAllocator::preflight_check_finish() { _preflight_check_running = false; @@ -628,22 +620,33 @@ void ControlAllocator::preflight_check_overwrite_torque_sp(matrix::VectorsetBypassTiltrotorControls(true, modified_tilt_control, 0.0f); + } else { + // Commanded collective tilt axis but the vehicle is not a tiltrotor. Abort + _preflight_check_running = false; + preflight_check_send_ack(vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED); - return modified_tilt_control; + } + } + } else { + PX4_INFO("preflight check not running"); + // strictly speaking this is only necessary if is_tiltrotor but + // can't hurt to call it always in case other + // ActuatorEffectiveness* classes implement similar things + _actuator_effectiveness->setBypassTiltrotorControls(false, 0.0f, 0.0f); + } } void diff --git a/src/modules/control_allocator/ControlAllocator.hpp b/src/modules/control_allocator/ControlAllocator.hpp index 439ba33aa66e..a9e82b541d4b 100644 --- a/src/modules/control_allocator/ControlAllocator.hpp +++ b/src/modules/control_allocator/ControlAllocator.hpp @@ -142,7 +142,7 @@ class ControlAllocator : public ModuleBase, public ModuleParam void preflight_check_overwrite_torque_sp(matrix::Vector (&c)[ActuatorEffectiveness::MAX_NUM_MATRICES]); void preflight_check_update_state(); - float preflight_check_get_tilt_control(); + void preflight_check_handle_tilt_control(); void preflight_check_start(vehicle_command_s &cmd); void preflight_check_send_ack(uint8_t result); void preflight_check_abort(); @@ -214,8 +214,6 @@ class ControlAllocator : public ModuleBase, public ModuleParam uint16_t _handled_motor_failure_bitmask{0}; bool _preflight_check_running{false}; - int _preflight_check_phase{0}; - hrt_abstime _last_preflight_check_update{0}; uint8_t _preflight_check_axis{0}; float _preflight_check_input{0.0f}; diff --git a/src/modules/mavlink/mavlink b/src/modules/mavlink/mavlink index 619947d8bc29..81aae2f75776 160000 --- a/src/modules/mavlink/mavlink +++ b/src/modules/mavlink/mavlink @@ -1 +1 @@ -Subproject commit 619947d8bc29e80eecff18b0f4fecc42d9e171dd +Subproject commit 81aae2f75776649aecd56a2afaba434bfbb2ab6f