Skip to content

Commit

Permalink
preflight check: polishing
Browse files Browse the repository at this point in the history
 - refactor last bit of logic from Run() into own method
 - update tiltrotor logic to new input (vehicle command rather than
   state machine)
 - remove unneeded member vars
 - format
  • Loading branch information
mbjd committed Feb 25, 2025
1 parent 2f7537b commit 2f13da3
Show file tree
Hide file tree
Showing 3 changed files with 26 additions and 25 deletions.
45 changes: 24 additions & 21 deletions src/modules/control_allocator/ControlAllocator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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();
}
Expand Down Expand Up @@ -563,7 +556,6 @@ void ControlAllocator::preflight_check_abort()

}


void ControlAllocator::preflight_check_finish()
{
_preflight_check_running = false;
Expand Down Expand Up @@ -628,22 +620,33 @@ void ControlAllocator::preflight_check_overwrite_torque_sp(matrix::Vector<float,
}
}

float ControlAllocator::preflight_check_get_tilt_control()
void ControlAllocator::preflight_check_handle_tilt_control()
{
bool is_tiltrotor = _effectiveness_source_id == EffectivenessSource::TILTROTOR_VTOL;

if (_preflight_check_running) {

int axis = _preflight_check_phase / 2;
int negative = _preflight_check_phase % 2;
if (_preflight_check_axis == vehicle_command_s::AXIS_COLLECTIVE_TILT) {

float modified_tilt_control = 0.5f;
if (is_tiltrotor) {
float modified_tilt_control = math::constrain(_preflight_check_input, 0.f, 1.f);

if (axis == 3) {
// axis 3 = tiltrotor.
// collective tilt normalised control goes from 0 to 1.
modified_tilt_control = negative ? 0.f : 1.f;
}
_actuator_effectiveness->setBypassTiltrotorControls(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
Expand Down
4 changes: 1 addition & 3 deletions src/modules/control_allocator/ControlAllocator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ class ControlAllocator : public ModuleBase<ControlAllocator>, public ModuleParam

void preflight_check_overwrite_torque_sp(matrix::Vector<float, NUM_AXES> (&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();
Expand Down Expand Up @@ -214,8 +214,6 @@ class ControlAllocator : public ModuleBase<ControlAllocator>, 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};
Expand Down

0 comments on commit 2f13da3

Please # to comment.