Skip to content
New issue

Have a question about this project? # for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “#”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? # to your account

Control surface preflight check #24391

Draft
wants to merge 31 commits into
base: main
Choose a base branch
from
Draft

Control surface preflight check #24391

wants to merge 31 commits into from

Conversation

mbjd
Copy link
Contributor

@mbjd mbjd commented Feb 21, 2025

Solved Problem

The current preflight check sends servo commands (essentially) directly over mavlink. This requires the GS to know/guess which actuators are available and should be tested.

Solution

(This describes the solution after bc86923, currently a slightly different version is WIP)

As an alternative solution, this control surface preflight check is triggered using a single command and decides on the PX4 side which specific actuators are used. It works as follows:

  • Started using VEHICLE_CMD_DO_PREFLIGHT_CS_CHECK, no parameters as of now.
  • Upon receiving that command ControlAllocator cycles through roll, pitch, yaw, and collective tilt, and tests the min/max setpoints for each one.
    • For this we must be prearmed (enable using param set COM_PREARM_MODE 2).
    • If armed, the command is rejected and if not pre-armed the actuators will do nothing.
    • If the vehicle is armed during the preflight check, it stops immediately.
  • Roll/pitch/yaw are implemented by modifying the torque setpoint before the allocator converts it to explicit servo setpoints. Therefore, it automatically works for all airframes supported by the allocator.
  • Collective tilt is handled by passing a modified setpoint to ActuatorEffectivenessTiltrotorVTOL with a setter function (declared for the base class ActuatorEffectiveness, but empty implementation unless overridden).

Here is a diagram depicting the information flow:
image

Alternatives / modifications

  • isolate everything related to preflight check in ControlAllocator into an own class
  • make state machine and timing configurable (e.g. via vehicle command parameters)
  • add functionality to test individual actuators back, replacing previous check

mbjd added 25 commits February 21, 2025 12:04
 - currently triggered via param COM_DO_CS_CHECK. ultimately this will
   be replaced by a mavlink cmd
 - new VehicleStatus.nav_state, NAVIGATION_STATE_CS_PREFLIGHT_CHECK.
   this is how commander tells ControlAllocator to conduct the check
 - (todo) within ControlAllocator we overwrite torque setpoints to do
   the check. additionally we can also control servos directly from
   there, in a different mode if that is needed.
not sure if all of these are needed, but with all of them the allocator
runs, and with only flag_control_allocation_enabled it does not.
modifies torque setpoints directly via the matrix c.
we "intercept" the tiltrotor_extra_controls message, which is read again
right after in ActuatorEffectivenessTiltrotorVTOL::updateSetpoint.
even if we are not currently testing the tilt axis. then we send zero
tilt rather than nothing.
previously it would always change _user_mode_intention to
_prev_nav_state forever. now we change it only if we are in preflight
check mode to not interfere with anything else later.
this adds a new flag to ActuatorEffectivenessTiltrotorVTOL:
_preflight_check_running. We set it from ControlAllocator, and if true
we always add collective tilt to the actuator setpoint.
Previously, the approach to modify collective tilt control was to send
the corresponding tiltrotor_extra_control uOrb message from
ControlAllocator, which then influences
ActuatorEffectivenessTiltrotorVTOL with minimal changes.

This was a bit hacky and introduced potentially conflicting uOrb
messages. So, with this new approach we pass the same information via
argument.

Specifically, the class ActuatorEffectiveness now declares
updateSetpoint with an extra argument, preflight_check_running. It is
only used in ActuatorEffectivenessTiltrotorVTOL, but has to be included
as a "dummy" in all other classes inheriting from ActuatorEffectiveness.

The argument can be used to bypass the collective tilt/thrust setpoints,
instead replacing them with values from public class member variables
which can be set from outside just before calling updateSetpoints.

Also, slight refactor in ControlAllocator by splitting up the functions
related to the preflight check into smaller parts
this allows us to have *only* the setter in the base class
(ActuatorEffectiveness) with an empty implementation. Derived classes
can implement another implementation, or stay completely unchanged
w.r.t. previously. This may finally be the desired clean-ish OOP-ish
solution to this.
put everything related to tiltrotor extra controls into own function to
clean up updateSetpoint
The preflight check can be enabled by switching to nav_state
vehicle_status_s::NAVIGATION_STATE_CS_PREFLIGHT_CHECK using
VEHICLE_CMD_SET_NAV_STATE. Thus we can ditch this function and forgo
adding an extra vehicle command.
and remove the parameter which ran it before.

also, print info about rejection if trying to run it while armed
previously it would continue running after one round, because the two
functions preflight_check_update_state and
preflight_check_overwrite_torque_sp were called within the same
preflight check running if clause, so updating _preflight_check_running
in the first would not stop the second from running.
Copy link

github-actions bot commented Feb 21, 2025

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 1160 byte (0.06 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.1% +1.13Ki  +0.1% +1.13Ki    .text
  +9.1%    +732  +9.1%    +732    ../../src/modules/control_allocator/ControlAllocator.cpp
  +0.1%    +165  +0.1%    +165    [section .text]
  +5.5%    +132  +5.5%    +132    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.6%    +128  +0.6%    +128    ../../src/modules/commander/Commander.cpp
  +1.3%      +4  +1.3%      +4    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  +0.2%      +3  +0.2%      +3    ../../src/systemcmds/ver/ver.cpp
  -0.1%      -4  -0.1%      -4    ../../src/modules/dataman/dataman.cpp
+0.0%    +302  [ = ]       0    .debug_abbrev
   +11%     +56  [ = ]       0    ../../src/lib/version/version.c
  +3.2%    +129  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  +4.2%    +117  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
+0.1%     +88  [ = ]       0    .debug_aranges
  +6.2%      +8  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -5.0%      -8  [ = ]       0    ../../src/lib/version/version.c
   +18%     +64  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
   +11%     +24  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
+0.1%    +288  [ = ]       0    .debug_frame
+0.0% +10.3Ki  [ = ]       0    .debug_info
  +0.3%     +76  [ = ]       0    ../../src/drivers/camera_capture/camera_capture.cpp
  +0.2%     +76  [ = ]       0    ../../src/drivers/camera_trigger/camera_trigger.cpp
  +0.1%     +76  [ = ]       0    ../../src/drivers/dshot/DShot.cpp
  +0.1%     +76  [ = ]       0    ../../src/drivers/px4io/px4io.cpp
  +0.2%     +76  [ = ]       0    ../../src/drivers/rc/dsm_rc/DsmRc.cpp
  +0.1%     +76  [ = ]       0    ../../src/drivers/rc_input/RCInput.cpp
  +0.3%     +76  [ = ]       0    ../../src/drivers/safety_button/SafetyButton.cpp
  +0.1%     +76  [ = ]       0    ../../src/drivers/uavcan/sensors/safety_button.cpp
  +0.0%     +77  [ = ]       0    ../../src/drivers/uavcan/uavcan_main.cpp
  +0.4%     +76  [ = ]       0    ../../src/lib/button/ButtonPublisher.cpp
  +0.1%     +76  [ = ]       0    ../../src/lib/collision_prevention/CollisionPrevention.cpp
  +0.7%    +129  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  +0.1%     +76  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -0.2%      -4  [ = ]       0    ../../src/lib/version/version.c
  +0.7%     +76  [ = ]       0    ../../src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp
  +0.1%    +121  [ = ]       0    ../../src/modules/commander/Commander.cpp
  +0.3%     +76  [ = ]       0    ../../src/modules/commander/calibration_routines.cpp
  +0.1%     +76  [ = ]       0    ../../src/modules/commander/failure_detector/FailureDetector.cpp
  +6.3% +6.10Ki  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  +0.6%    +325  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
 -99.9% +2.53Ki  [ = ]       0    [34 Others]
+0.0% +2.00Ki  [ = ]       0    .debug_line
  +1.2%     +22  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -1.3%     -25  [ = ]       0    ../../src/lib/version/version.c
  +0.1%     +40  [ = ]       0    ../../src/modules/commander/Commander.cpp
  +7.9% +1.43Ki  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  +8.4%    +540  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.4%      +4  [ = ]       0    task/task_cancelpt.c
+0.1% +2.77Ki  [ = ]       0    .debug_loc
  -0.0%     -15  [ = ]       0    ../../src/drivers/uavcan/uavcan_main.cpp
  +0.0%     +17  [ = ]       0    ../../src/drivers/uavcan/uavcan_servers.cpp
  -0.3%     -15  [ = ]       0    ../../src/lib/adsb/AdsbConflict.cpp
  -0.1%     -15  [ = ]       0    ../../src/lib/collision_prevention/CollisionPrevention.cpp
  +0.3%    +108  [ = ]       0    ../../src/modules/commander/Commander.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/commander/failure_detector/FailureDetector.cpp
  +9.9% +2.17Ki  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  +4.4%    +372  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  -0.2%     -15  [ = ]       0    ../../src/modules/flight_mode_manager/FlightModeManager.cpp
  -0.0%     -16  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/AutoFollowTarget/FlightTaskAutoFollowTarget.cpp
  -0.1%     -16  [ = ]       0    ../../src/modules/navigator/navigator_main.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/navigator/rtl.cpp
  -0.2%     -15  [ = ]       0    ../../src/modules/navigator/rtl_direct.cpp
  +0.2%     +15  [ = ]       0    ../../src/modules/navigator/rtl_direct_mission_land.cpp
  -0.3%     -15  [ = ]       0    ../../src/modules/temperature_compensation/TemperatureCompensationModule.cpp
  -0.2%     -15  [ = ]       0    ../../src/modules/vtol_att_control/vtol_att_control_main.cpp
  +0.1%    +263  [ = ]       0    [section .debug_loc]
  -0.0%     -39  [ = ]       0    src/modules/ekf2/modules__ekf2_unity.cpp
  +0.0%     +45  [ = ]       0    src/modules/mavlink/modules__mavlink_unity.cpp
+0.0%    +534  [ = ]       0    .debug_ranges
  +4.3%      +8  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -2.6%      -8  [ = ]       0    ../../src/lib/version/version.c
  +0.1%      +8  [ = ]       0    ../../src/modules/commander/Commander.cpp
  +7.9%    +640  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  -5.1%    -136  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.0%     +24  [ = ]       0    [section .debug_ranges]
  -3.0%      -2  [ = ]       0    task/task_cancelpt.c
+0.0% +1.26Ki  [ = ]       0    .debug_str
  +1.1%     +85  [ = ]       0    ../../src/drivers/camera_capture/camera_capture.cpp
   +23%     +59  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  +2.6%    +898  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  +1.2%     +14  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessRotors.cpp
   +26%    +286  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  -0.4%     -14  [ = ]       0    ../../src/modules/landing_target_estimator/landing_target_estimator_main.cpp
  -5.1%     -18  [ = ]       0    ../../src/modules/mc_pos_control/PositionControl/PositionControl.cpp
  +0.7%      +5  [ = ]       0    ../../src/modules/vtol_att_control/tailsitter.cpp
  -0.5%     -14  [ = ]       0    ../../src/modules/vtol_att_control/tiltrotor.cpp
  -0.0%      -9  [ = ]       0    src/modules/mavlink/modules__mavlink_unity.cpp
-1.0%      -2  [ = ]       0    .shstrtab
+0.1%    +486  [ = ]       0    .strtab
   +23%     +59  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -8.1%     -32  [ = ]       0    ../../src/lib/version/version.c
   +11%    +177  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
   +15%    +250  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.0%     +32  [ = ]       0    [section .strtab]
+0.1%    +320  [ = ]       0    .symtab
  -1.3%     -16  [ = ]       0    ../../src/drivers/power_monitor/ina228/ina228.cpp
  -0.4%     -16  [ = ]       0    ../../src/drivers/uavcan/sensors/sensor_bridge.cpp
   +18%     +32  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -7.0%     -64  [ = ]       0    ../../src/lib/version/version.c
  +0.7%     +32  [ = ]       0    ../../src/modules/commander/Commander.cpp
  +8.5%    +160  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
   +12%     +96  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.3%     +16  [ = ]       0    ../../src/modules/fw_pos_control/FixedwingPositionControl.cpp
  +0.1%     +80  [ = ]       0    [section .symtab]
-6.2% -1.13Ki  [ = ]       0    [Unmapped]
+0.0% +18.3Ki  +0.1% +1.13Ki    TOTAL

px4_fmu-v6x [Total VM Diff: 1144 byte (0.06 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.1% +1.12Ki  +0.1% +1.12Ki    .text
  +9.1%    +732  +9.1%    +732    ../../src/modules/control_allocator/ControlAllocator.cpp
  +0.1%    +152  +0.1%    +152    [section .text]
  +5.5%    +132  +5.5%    +132    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.6%    +128  +0.6%    +128    ../../src/modules/commander/Commander.cpp
  +1.3%      +4  +1.3%      +4    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -0.1%      -4  -0.1%      -4    ../../src/modules/dataman/dataman.cpp
+0.0%    +302  [ = ]       0    .debug_abbrev
   +11%     +56  [ = ]       0    ../../src/lib/version/version.c
  +3.2%    +129  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  +4.2%    +117  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
+0.1%     +88  [ = ]       0    .debug_aranges
  +6.2%      +8  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -5.0%      -8  [ = ]       0    ../../src/lib/version/version.c
   +18%     +64  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
   +11%     +24  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
+0.1%    +288  [ = ]       0    .debug_frame
+0.0% +10.2Ki  [ = ]       0    .debug_info
  +0.3%     +76  [ = ]       0    ../../src/drivers/camera_capture/camera_capture.cpp
  +0.2%     +76  [ = ]       0    ../../src/drivers/camera_trigger/camera_trigger.cpp
  +0.1%     +76  [ = ]       0    ../../src/drivers/dshot/DShot.cpp
  +0.1%     +76  [ = ]       0    ../../src/drivers/px4io/px4io.cpp
  +0.1%     +76  [ = ]       0    ../../src/drivers/rc_input/RCInput.cpp
  +0.3%     +76  [ = ]       0    ../../src/drivers/safety_button/SafetyButton.cpp
  +0.1%     +76  [ = ]       0    ../../src/drivers/uavcan/sensors/safety_button.cpp
  +0.0%     +77  [ = ]       0    ../../src/drivers/uavcan/uavcan_main.cpp
  +0.4%     +76  [ = ]       0    ../../src/lib/button/ButtonPublisher.cpp
  +0.1%     +76  [ = ]       0    ../../src/lib/collision_prevention/CollisionPrevention.cpp
  +0.7%    +129  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  +0.1%     +76  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -0.2%      -4  [ = ]       0    ../../src/lib/version/version.c
  +0.7%     +76  [ = ]       0    ../../src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp
  +0.1%    +121  [ = ]       0    ../../src/modules/commander/Commander.cpp
  +0.3%     +76  [ = ]       0    ../../src/modules/commander/calibration_routines.cpp
  +0.1%     +76  [ = ]       0    ../../src/modules/commander/failure_detector/FailureDetector.cpp
  +6.3% +6.10Ki  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  +0.6%    +325  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.2%     +76  [ = ]       0    ../../src/modules/events/send_event.cpp
 -99.9% +2.38Ki  [ = ]       0    [32 Others]
+0.0% +1.99Ki  [ = ]       0    .debug_line
  +1.2%     +22  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -1.3%     -25  [ = ]       0    ../../src/lib/version/version.c
  +0.1%     +40  [ = ]       0    ../../src/modules/commander/Commander.cpp
  +7.9% +1.43Ki  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  +8.4%    +540  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  -0.3%      -3  [ = ]       0    task/task_cancelpt.c
+0.1% +2.71Ki  [ = ]       0    .debug_loc
  -0.5%     -15  [ = ]       0    ../../src/drivers/camera_capture/camera_capture.cpp
  +0.1%     +15  [ = ]       0    ../../src/drivers/px4io/px4io.cpp
  -0.0%     -33  [ = ]       0    ../../src/drivers/uavcan/uavcan_main.cpp
  +0.0%      +1  [ = ]       0    ../../src/drivers/uavcan/uavcan_servers.cpp
  -0.1%     -15  [ = ]       0    ../../src/lib/collision_prevention/CollisionPrevention.cpp
  -0.1%     -16  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  +0.3%    +108  [ = ]       0    ../../src/modules/commander/Commander.cpp
  +9.9% +2.17Ki  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  +4.0%    +339  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  -0.0%     -16  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/AutoFollowTarget/FlightTaskAutoFollowTarget.cpp
  -0.0%     -15  [ = ]       0    ../../src/modules/fw_pos_control/FixedwingPositionControl.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/navigator/navigator_main.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/navigator/rtl.cpp
  -0.2%     -15  [ = ]       0    ../../src/modules/vtol_att_control/vtol_att_control_main.cpp
  +0.1%    +261  [ = ]       0    [section .debug_loc]
  -0.0%     -32  [ = ]       0    src/modules/ekf2/modules__ekf2_unity.cpp
  +0.0%     +15  [ = ]       0    src/modules/mavlink/modules__mavlink_unity.cpp
+0.0%    +536  [ = ]       0    .debug_ranges
  +4.3%      +8  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -2.6%      -8  [ = ]       0    ../../src/lib/version/version.c
  +0.1%      +8  [ = ]       0    ../../src/modules/commander/Commander.cpp
  +7.9%    +640  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  -5.1%    -136  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.1%     +24  [ = ]       0    [section .debug_ranges]
+0.0% +1.26Ki  [ = ]       0    .debug_str
  +1.1%     +85  [ = ]       0    ../../src/drivers/camera_capture/camera_capture.cpp
   +23%     +59  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  +2.6%    +898  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
  +1.2%     +14  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessRotors.cpp
   +26%    +286  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  -0.4%     -14  [ = ]       0    ../../src/modules/landing_target_estimator/landing_target_estimator_main.cpp
  -5.1%     -18  [ = ]       0    ../../src/modules/mc_pos_control/PositionControl/PositionControl.cpp
  +0.7%      +5  [ = ]       0    ../../src/modules/vtol_att_control/tailsitter.cpp
  -0.5%     -14  [ = ]       0    ../../src/modules/vtol_att_control/tiltrotor.cpp
  -0.0%      -9  [ = ]       0    src/modules/mavlink/modules__mavlink_unity.cpp
-0.9%      -2  [ = ]       0    .shstrtab
+0.1%    +486  [ = ]       0    .strtab
   +23%     +59  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -8.1%     -32  [ = ]       0    ../../src/lib/version/version.c
   +11%    +177  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
   +15%    +250  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.0%     +32  [ = ]       0    [section .strtab]
+0.1%    +320  [ = ]       0    .symtab
   +20%     +32  [ = ]       0    ../../src/lib/control_allocation/actuator_effectiveness/ActuatorEffectiveness.cpp
  -7.0%     -64  [ = ]       0    ../../src/lib/version/version.c
  +0.7%     +32  [ = ]       0    ../../src/modules/commander/Commander.cpp
  +8.5%    +160  [ = ]       0    ../../src/modules/control_allocator/ControlAllocator.cpp
   +12%     +96  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.3%     +16  [ = ]       0    ../../src/modules/fw_pos_control/FixedwingPositionControl.cpp
  +0.1%     +48  [ = ]       0    [section .symtab]
-1.5% -1.12Ki  [ = ]       0    [Unmapped]
+0.0% +18.1Ki  +0.1% +1.12Ki    TOTAL

Updated: 2025-02-24T15:50:37

mbjd added 2 commits February 21, 2025 15:10
 - only publish ack if we got the right command initially
 - fix state machine (don't jump from 0 to 1 immediately)
 - comments, docstrings
 - move command next to previous one
@mbjd mbjd force-pushed the cs_preflight_check_3 branch 2 times, most recently from fb98635 to f010c75 Compare February 25, 2025 07:38
previously, one command without params started the entire check.

here this is changed to including axis (roll, pitch, yaw, ...) and
deflection in the vehicle command. idea being that ground control
can implement a nice slider to actuate rpy.

commander cs_check atm does only one hardcoded axis/deflection combo.
@mbjd mbjd force-pushed the cs_preflight_check_3 branch 3 times, most recently from 2f13da3 to a815643 Compare February 25, 2025 09:55
mbjd added 3 commits February 25, 2025 11:21
 - 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
@mbjd mbjd force-pushed the cs_preflight_check_3 branch from a815643 to d1e18c1 Compare February 25, 2025 10:24
# for free to join this conversation on GitHub. Already have an account? # to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

1 participant