Skip to content

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

As an alternative solution, this check tests control surfaces in functional groups (roll/pitch/yaw/tilt). It works as follows:

  • Started using VEHICLE_CMD_DO_PREFLIGHT_CS_CHECK, containing parameters: axis (roll/pitch/yaw/tilt) and control input.
  • Upon receiving that command, ControlAllocator applies the given control input to the given axis.
    • 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

Copy link

github-actions bot commented Feb 21, 2025

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 1864 byte (0.09 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.1% +1.82Ki  +0.1% +1.82Ki    .text
  [NEW]    +720  [NEW]    +720    ActuatorEffectivenessTiltrotorVTOL::processTiltrotorControls()
  +0.3%    +444  +0.3%    +444    [section .text]
   +13%    +288   +13%    +288    Commander::custom_command()
  [NEW]    +264  [NEW]    +264    ControlAllocator::preflight_check_handle_command()
  [NEW]    +128  [NEW]    +128    ControlAllocator::preflight_check_send_ack()
   +11%    +116   +11%    +116    ControlAllocator::Run()
  [NEW]    +108  [NEW]    +108    ControlAllocator::preflight_check_handle_tilt_control()
  [NEW]    +104  [NEW]    +104    ControlAllocator::preflight_check_update_state()
 +10.0%     +88 +10.0%     +88    ControlAllocator::ControlAllocator()
  +1.9%     +64  +1.9%     +64    Commander::handle_command()
 -97.7%     +60 -97.7%     +60    [19 Others]
  [NEW]     +56  [NEW]     +56    CSWTCH.280
   +13%     +52   +13%     +52    Commander::print_usage()
  [NEW]     +32  [NEW]     +32    ActuatorEffectivenessTiltrotorVTOL::overrideCollectiveTilt()
  [NEW]     +32  [NEW]     +32    CSWTCH.276
  +4.5%     +16  +4.5%     +16    ActuatorEffectivenessTiltrotorVTOL::ActuatorEffectivenessTiltrotorVTOL()
  +3.8%     +16  +3.8%     +16    ControlAllocator::~ControlAllocator()
  +6.7%      +8  +6.7%      +8    ActuatorEffectivenessTiltrotorVTOL
  [DEL]     -32  [DEL]     -32    CSWTCH.274
  [DEL]     -56  [DEL]     -56    CSWTCH.278
 -85.2%    -644 -85.2%    -644    ActuatorEffectivenessTiltrotorVTOL::updateSetpoint()
+100%      +8  [ = ]       0    .ARM.exidx
+0.0%    +313  [ = ]       0    .debug_abbrev
+0.1%     +88  [ = ]       0    .debug_aranges
+0.1%    +300  [ = ]       0    .debug_frame
+0.0% +13.1Ki  [ = ]       0    .debug_info
+0.0% +1.94Ki  [ = ]       0    .debug_line
  +500%      +5  [ = ]       0    [Unmapped]
  +0.0% +1.94Ki  [ = ]       0    [section .debug_line]
+0.1% +3.02Ki  [ = ]       0    .debug_loclists
+0.0%    +268  [ = ]       0    .debug_rnglists
 -50.0%      -1  [ = ]       0    [Unmapped]
  +0.0%    +269  [ = ]       0    [section .debug_rnglists]
+0.0% +1.55Ki  [ = ]       0    .debug_str
+0.1%    +404  [ = ]       0    .strtab
  [NEW]     +54  [ = ]       0    ActuatorEffectiveness::overrideCollectiveTilt()
  [NEW]    +140  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::overrideCollectiveTilt()
  [NEW]    +100  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::processTiltrotorControls()
 -34.1%    -112  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::updateSetpoint()
  [DEL]     -11  [ = ]       0    CSWTCH.274
  [NEW]     +11  [ = ]       0    CSWTCH.276
  [DEL]     -11  [ = ]       0    CSWTCH.278
  [NEW]     +11  [ = ]       0    CSWTCH.280
  [DEL]     -11  [ = ]       0    CSWTCH.857
  [NEW]     +11  [ = ]       0    CSWTCH.860
  [NEW]     +56  [ = ]       0    ControlAllocator::preflight_check_handle_command()
  [NEW]     +61  [ = ]       0    ControlAllocator::preflight_check_handle_tilt_control()
  [NEW]     +51  [ = ]       0    ControlAllocator::preflight_check_send_ack()
  [NEW]     +54  [ = ]       0    ControlAllocator::preflight_check_update_state()
 -12.8%     -16  [ = ]       0    ___ZN39ControlAllocationSequentialDesaturation23computeDesaturationGainERKN6matrix6VectorIfLj16EEES4__veneer
   +62%     +16  [ = ]       0    __perf_set_elapsed_veneer
+0.1%    +352  [ = ]       0    .symtab
  [NEW]     +16  [ = ]       0    ActuatorEffectiveness::overrideCollectiveTilt()
 -25.0%     -16  [ = ]       0    ActuatorEffectiveness::stopMaskedMotorsWithZeroThrust()
 -14.3%     -16  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::getUnallocatedControl()
 -14.3%     -16  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::name()
  [NEW]     +32  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::overrideCollectiveTilt()
  [NEW]     +48  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::processTiltrotorControls()
 -42.9%     -48  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::updateSetpoint()
  [DEL]     -32  [ = ]       0    CSWTCH.274
  [NEW]     +32  [ = ]       0    CSWTCH.276
  [DEL]     -32  [ = ]       0    CSWTCH.278
  [NEW]     +32  [ = ]       0    CSWTCH.280
  [DEL]     -32  [ = ]       0    CSWTCH.857
  [NEW]     +32  [ = ]       0    CSWTCH.860
  +7.7%     +32  [ = ]       0    Commander::handle_command()
  [NEW]     +48  [ = ]       0    ControlAllocator::preflight_check_handle_command()
  [NEW]     +64  [ = ]       0    ControlAllocator::preflight_check_handle_tilt_control()
  [NEW]     +64  [ = ]       0    ControlAllocator::preflight_check_send_ack()
  [NEW]     +64  [ = ]       0    ControlAllocator::preflight_check_update_state()
 -16.7%     -16  [ = ]       0    ControlAllocator::update_effectiveness_source()
  +0.8%     +96  [ = ]       0    [section .symtab]
-19.1% -1.83Ki  [ = ]       0    [Unmapped]
+0.0% +21.3Ki  +0.1% +1.82Ki    TOTAL

px4_fmu-v6x [Total VM Diff: 1864 byte (0.1 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.1% +1.82Ki  +0.1% +1.82Ki    .text
  [NEW]    +720  [NEW]    +720    ActuatorEffectivenessTiltrotorVTOL::processTiltrotorControls()
  +0.3%    +444  +0.3%    +444    [section .text]
   +13%    +288   +13%    +288    Commander::custom_command()
  [NEW]    +264  [NEW]    +264    ControlAllocator::preflight_check_handle_command()
  [NEW]    +128  [NEW]    +128    ControlAllocator::preflight_check_send_ack()
   +11%    +116   +11%    +116    ControlAllocator::Run()
  [NEW]    +108  [NEW]    +108    ControlAllocator::preflight_check_handle_tilt_control()
  [NEW]    +104  [NEW]    +104    ControlAllocator::preflight_check_update_state()
 +10.0%     +88 +10.0%     +88    ControlAllocator::ControlAllocator()
  +1.9%     +64  +1.9%     +64    Commander::handle_command()
 -97.7%     +60 -97.7%     +60    [19 Others]
  [NEW]     +56  [NEW]     +56    CSWTCH.280
   +13%     +52   +13%     +52    Commander::print_usage()
  [NEW]     +32  [NEW]     +32    ActuatorEffectivenessTiltrotorVTOL::overrideCollectiveTilt()
  [NEW]     +32  [NEW]     +32    CSWTCH.276
  +4.5%     +16  +4.5%     +16    ActuatorEffectivenessTiltrotorVTOL::ActuatorEffectivenessTiltrotorVTOL()
  +3.8%     +16  +3.8%     +16    ControlAllocator::~ControlAllocator()
  +6.7%      +8  +6.7%      +8    ActuatorEffectivenessTiltrotorVTOL
  [DEL]     -32  [DEL]     -32    CSWTCH.274
  [DEL]     -56  [DEL]     -56    CSWTCH.278
 -85.2%    -644 -85.2%    -644    ActuatorEffectivenessTiltrotorVTOL::updateSetpoint()
+0.0%    +313  [ = ]       0    .debug_abbrev
+0.1%     +88  [ = ]       0    .debug_aranges
+0.1%    +300  [ = ]       0    .debug_frame
+0.0% +13.0Ki  [ = ]       0    .debug_info
+0.0% +1.94Ki  [ = ]       0    .debug_line
  [NEW]      +7  [ = ]       0    [Unmapped]
  +0.0% +1.94Ki  [ = ]       0    [section .debug_line]
+0.1% +3.04Ki  [ = ]       0    .debug_loclists
+0.0%    +271  [ = ]       0    .debug_rnglists
  +200%      +2  [ = ]       0    [Unmapped]
  +0.0%    +269  [ = ]       0    [section .debug_rnglists]
+0.0% +1.55Ki  [ = ]       0    .debug_str
+0.1%    +404  [ = ]       0    .strtab
  [NEW]     +54  [ = ]       0    ActuatorEffectiveness::overrideCollectiveTilt()
  [NEW]    +140  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::overrideCollectiveTilt()
  [NEW]    +100  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::processTiltrotorControls()
 -34.1%    -112  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::updateSetpoint()
  [DEL]     -11  [ = ]       0    CSWTCH.274
  [NEW]     +11  [ = ]       0    CSWTCH.276
  [DEL]     -11  [ = ]       0    CSWTCH.278
  [NEW]     +11  [ = ]       0    CSWTCH.280
  [DEL]     -11  [ = ]       0    CSWTCH.857
  [NEW]     +11  [ = ]       0    CSWTCH.860
  [NEW]     +56  [ = ]       0    ControlAllocator::preflight_check_handle_command()
  [NEW]     +61  [ = ]       0    ControlAllocator::preflight_check_handle_tilt_control()
  [NEW]     +51  [ = ]       0    ControlAllocator::preflight_check_send_ack()
  [NEW]     +54  [ = ]       0    ControlAllocator::preflight_check_update_state()
+0.1%    +352  [ = ]       0    .symtab
  [NEW]     +16  [ = ]       0    ActuatorEffectiveness::overrideCollectiveTilt()
 -25.0%     -16  [ = ]       0    ActuatorEffectiveness::stopMaskedMotorsWithZeroThrust()
 -14.3%     -16  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::getUnallocatedControl()
 -14.3%     -16  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::name()
  [NEW]     +32  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::overrideCollectiveTilt()
  [NEW]     +48  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::processTiltrotorControls()
 -42.9%     -48  [ = ]       0    ActuatorEffectivenessTiltrotorVTOL::updateSetpoint()
  [DEL]     -32  [ = ]       0    CSWTCH.274
  [NEW]     +32  [ = ]       0    CSWTCH.276
  [DEL]     -32  [ = ]       0    CSWTCH.278
  [NEW]     +32  [ = ]       0    CSWTCH.280
  [DEL]     -32  [ = ]       0    CSWTCH.857
  [NEW]     +32  [ = ]       0    CSWTCH.860
  +7.7%     +32  [ = ]       0    Commander::handle_command()
  [NEW]     +48  [ = ]       0    ControlAllocator::preflight_check_handle_command()
  [NEW]     +64  [ = ]       0    ControlAllocator::preflight_check_handle_tilt_control()
  [NEW]     +64  [ = ]       0    ControlAllocator::preflight_check_send_ack()
  [NEW]     +64  [ = ]       0    ControlAllocator::preflight_check_update_state()
 -16.7%     -16  [ = ]       0    ControlAllocator::update_effectiveness_source()
  +0.8%     +96  [ = ]       0    [section .symtab]
 +42% +2.18Ki  [ = ]       0    [Unmapped]
+0.1% +25.2Ki  +0.1% +1.82Ki    TOTAL

Updated: 2025-07-16T09:17:00

@ryanjAA
Copy link
Contributor

ryanjAA commented Mar 8, 2025

This is great. A CS preflight command QGC side is the logical next step that allows you to hit a button and have all CS move to min max move rather than a manual check. Awesome.

@mbjd mbjd force-pushed the cs_preflight_check_3 branch from e9c709b to b0de604 Compare July 3, 2025 12:53
@mbjd mbjd force-pushed the cs_preflight_check_3 branch from b0de604 to 9e4b058 Compare July 3, 2025 13:02
@mbjd mbjd marked this pull request as ready for review July 3, 2025 13:02
@mbjd mbjd force-pushed the cs_preflight_check_3 branch from b162d35 to c75ea70 Compare July 14, 2025 07:50
Copy link
Contributor

@sfuhrer sfuhrer left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I have mostly nitpicks here, you did a good job in adding this functionality to an architecture that didn't plan for it.
We need to align on the wording of the mavlink message.


if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_DO_PREFLIGHT_CS_CHECK) {
if (!_armed) {
// currently this does not check prearmed status. if not prearmed, it will just do nothing.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Would be good to notify the user, yes.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

checking for prearmed state now. I added a subscription to actuator_armed to get it, I presume there's not a neater way, or can you think of one?

uORB::Subscription _tiltrotor_extra_controls_sub{ORB_ID(tiltrotor_extra_controls)};

bool _bypass_tiltrotor_controls{false};
float _collective_tilt_normalized_setpoint{0.5f};
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do we need both that and _last_collective_tilt_control? Can we remove some of these class members? They add memory and through that complexity.

Copy link
Contributor Author

@mbjd mbjd Jul 16, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd keep them both as they serve different purposes:

  • _last_collective_tilt_control is populated in processTiltrotorControls, thus acts as an output wrt. that function. It is used to construct the effectivenes matrix. note that is is not actually the last collective tilt control -- it is modified here to achieve desired transition behaviour with a "wrong" effectiveness matrix...
  • _collective_tilt_normalized_setpoint is an input to processTiltrotorControls, only in the case of overriding collective tilt introduced here.

I suppose it would be technically possible to unify them, especially if we guarantee that we will never be in a preflight check and a transition at the same time. But mixing input/output functionality would imo be confusing and hinder maintainability, and we'd have to remove / move / work around the hack of sometimes outputting the wrong collective tilt.

@mbjd
Copy link
Contributor Author

mbjd commented Jul 16, 2025

Please don't merge before before mavlink/mavlink#2224

@mbjd mbjd force-pushed the cs_preflight_check_3 branch from 6ecc76d to 2d76534 Compare July 16, 2025 09:10
@hamishwillee
Copy link
Contributor

Please don't merge before before mavlink/mavlink#2224

I still need to get someone from ArduPilot to look at the mavlink PR. I've been trying and will continue to do so. Ping me next week if it has not merged.

@dagar dagar marked this pull request as draft August 7, 2025 16:15
@github-actions github-actions bot added the stale label Sep 16, 2025
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

Projects

None yet

Development

Successfully merging this pull request may close these issues.

5 participants