Skip to content

Conversation

RomanBapst
Copy link
Contributor

@RomanBapst RomanBapst commented Nov 29, 2024

Solved Problem

Because of the convoluted manner of the current high level fixed-wing controller architecture, it is not possible to cleanly implement an external flight mode that is interacting with PX4 over e.g. height rate, course and lateral acceleration setpoints.
In this PR we rework the FW position controller to expose clean APIs for lateral and longitudinal control.

Screenshot from 2025-03-11 15-36-11

image

Changelog Entry

For release notes:

Feature: Rework the FW position controller to expose clean APIs for lateral and longitudinal control.

TODO

  • Finish testing list below
  • Finalize handling of control limits
  • Verify that fixed wing auto-takeoff and auto-landing still work as intended
  • Solve Flash

Alternatives

Test coverage

Flight test:

  • Manual modes Stabilized, Altitude, Position
  • Auto Hold
  • Auto Mission
  • RTL
  • Hand-launch takeoff
  • Runway takeoff
  • Auto landing
  • Airspeed failure in-air
  • GPS-denied
  • Tailsitter specific testing (check rotations are correct)

Copy link

github-actions bot commented Dec 20, 2024

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 4596 byte (0.23 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.2% +4.47Ki  +0.2% +4.47Ki    .text
 -98.3% +7.63Ki -98.3% +7.63Ki    [268 Others]
  [NEW] +2.23Ki  [NEW] +2.23Ki    FixedWingModeManager::FixedWingModeManager()
  [NEW] +1.86Ki  [NEW] +1.86Ki    FixedWingModeManager::Run()
  [NEW] +1.56Ki  [NEW] +1.56Ki    FwLateralLongitudinalControl::Run()
  [NEW] +1.44Ki  [NEW] +1.44Ki    FwLateralLongitudinalControl::FwLateralLongitudinalControl()
  [NEW] +1.35Ki  [NEW] +1.35Ki    FixedWingModeManager::control_auto_landing_straight()
  [NEW] +1.30Ki  [NEW] +1.30Ki    FixedWingModeManager::control_auto_takeoff()
  [NEW] +1.14Ki  [NEW] +1.14Ki    FixedWingModeManager::control_auto_landing_circular()
  [NEW]    +696  [NEW]    +696    FixedWingModeManager::vehicle_attitude_poll()
  [DEL]    -608  [DEL]    -608    FixedwingPositionControl::vehicle_attitude_poll()
  [DEL]    -616  [DEL]    -616    NPFG::guideToPath()
  [DEL]    -632  [DEL]    -632    FixedwingPositionControl::parameters_update()
  [DEL]    -684  [DEL]    -684    FixedwingPositionControl::control_auto_position()
  [DEL]    -788  [DEL]    -788    FixedwingPositionControl::control_manual_position()
  [DEL]    -828  [DEL]    -828    FixedwingPositionControl::control_auto_loiter()
  [DEL]    -842  [DEL]    -842    FixedwingPositionControl::updateParamsImpl()
  [DEL] -1.39Ki  [DEL] -1.39Ki    FixedwingPositionControl::control_auto_landing_circular()
  [DEL] -1.57Ki  [DEL] -1.57Ki    FixedwingPositionControl::control_auto_landing_straight()
  [DEL] -1.64Ki  [DEL] -1.64Ki    FixedwingPositionControl::control_auto_takeoff()
  [DEL] -2.32Ki  [DEL] -2.32Ki    FixedwingPositionControl::Run()
  [DEL] -2.91Ki  [DEL] -2.91Ki    FixedwingPositionControl::FixedwingPositionControl()
+0.1%     +16  +0.1%     +16    .ramfunc
  +1.7%      +4  +1.7%      +4    param_get
  +1.4%      +4  +1.4%      +4    param_get_default_value
   +33%      +4   +33%      +4    param_get_index
  +9.1%      +4  +9.1%      +4    param_get_system_default_value
+1.0%      +4  +1.0%      +4    .init_section
+0.7% +13.1Ki  [ = ]       0    .debug_abbrev
+0.5%    +824  [ = ]       0    .debug_aranges
+0.4% +1.69Ki  [ = ]       0    .debug_frame
+0.7%  +192Ki  [ = ]       0    .debug_info
+0.5% +24.2Ki  [ = ]       0    .debug_line
+0.3% +9.56Ki  [ = ]       0    .debug_loclists
+0.1%    +377  [ = ]       0    .debug_rnglists
   +50%      +1  [ = ]       0    [Unmapped]
  +0.1%    +376  [ = ]       0    [section .debug_rnglists]
+0.2% +8.23Ki  [ = ]       0    .debug_str
+1.3%      +3  [ = ]       0    .shstrtab
+0.6% +3.85Ki  [ = ]       0    .strtab
  [NEW]     +74  [ = ]       0    AirspeedDirectionController::AirspeedDirectionController()
  [NEW]     +54  [ = ]       0    AirspeedDirectionController::controlHeading()
  [NEW]      +7  [ = ]       0    C.54.0
  [DEL]      -7  [ = ]       0    C.60.0
  [NEW]     +73  [ = ]       0    CombinedControllerConfigurationHandler::floatValueChanged()
  [NEW]     +68  [ = ]       0    CombinedControllerConfigurationHandler::resetLastPublishTime()
  [NEW]     +66  [ = ]       0    CombinedControllerConfigurationHandler::setClimbRateTarget()
  [NEW]     +78  [ = ]       0    CombinedControllerConfigurationHandler::setDisableUnderspeedProtection()
  [NEW]     +76  [ = ]       0    CombinedControllerConfigurationHandler::setEnforceLowHeightCondition()
  [NEW]     +66  [ = ]       0    CombinedControllerConfigurationHandler::setLateralAccelMax()
  [NEW]     +59  [ = ]       0    CombinedControllerConfigurationHandler::setPitchMax()
  [NEW]     +59  [ = ]       0    CombinedControllerConfigurationHandler::setPitchMin()
  [NEW]     +65  [ = ]       0    CombinedControllerConfigurationHandler::setSinkRateTarget()
  [NEW]     +62  [ = ]       0    CombinedControllerConfigurationHandler::setSpeedWeight()
  [NEW]     +62  [ = ]       0    CombinedControllerConfigurationHandler::setThrottleMax()
  [NEW]     +62  [ = ]       0    CombinedControllerConfigurationHandler::setThrottleMin()
  [NEW]     +53  [ = ]       0    CombinedControllerConfigurationHandler::update()
  [NEW]     +91  [ = ]       0    CourseToAirspeedRefMapper::getMinAirspeedForCurrentBearing()
  [NEW]     +81  [ = ]       0    CourseToAirspeedRefMapper::infeasibleAirVelRef()
  [NEW]     +93  [ = ]       0    CourseToAirspeedRefMapper::mapCourseSetpointToHeadingSetpoint()
 -96.1% +2.64Ki  [ = ]       0    [218 Others]
+0.4% +2.53Ki  [ = ]       0    .symtab
  [NEW]     +80  [ = ]       0    AirspeedDirectionController::AirspeedDirectionController()
  [NEW]     +32  [ = ]       0    AirspeedDirectionController::controlHeading()
  [NEW]     +32  [ = ]       0    C.54.0
  [DEL]     -32  [ = ]       0    C.60.0
  [NEW]     +48  [ = ]       0    CombinedControllerConfigurationHandler::floatValueChanged()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::resetLastPublishTime()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setClimbRateTarget()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setDisableUnderspeedProtection()
  [NEW]     +48  [ = ]       0    CombinedControllerConfigurationHandler::setEnforceLowHeightCondition()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setLateralAccelMax()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setPitchMax()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setPitchMin()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setSinkRateTarget()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setSpeedWeight()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setThrottleMax()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setThrottleMin()
  [NEW]     +48  [ = ]       0    CombinedControllerConfigurationHandler::update()
 -33.3%     -16  [ = ]       0    ConstLayer::contains()
   +50%     +16  [ = ]       0    ConstLayer::store()
  [NEW]     +48  [ = ]       0    CourseToAirspeedRefMapper::getMinAirspeedForCurrentBearing()
 -96.0% +1.92Ki  [ = ]       0    [236 Others]
-5.3%    -500  [ = ]       0    [Unmapped]
+0.6%  +261Ki  +0.2% +4.49Ki    TOTAL

px4_fmu-v6x [Total VM Diff: 4524 byte (0.24 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.2% +4.41Ki  +0.2% +4.41Ki    .text
 -97.6% +6.37Ki -97.6% +6.37Ki    [256 Others]
  [NEW] +2.23Ki  [NEW] +2.23Ki    FixedWingModeManager::FixedWingModeManager()
  [NEW] +1.86Ki  [NEW] +1.86Ki    FixedWingModeManager::Run()
  [NEW] +1.56Ki  [NEW] +1.56Ki    FwLateralLongitudinalControl::Run()
  [NEW] +1.44Ki  [NEW] +1.44Ki    FwLateralLongitudinalControl::FwLateralLongitudinalControl()
  [NEW] +1.35Ki  [NEW] +1.35Ki    FixedWingModeManager::control_auto_landing_straight()
  [NEW] +1.30Ki  [NEW] +1.30Ki    FixedWingModeManager::control_auto_takeoff()
  [NEW] +1.14Ki  [NEW] +1.14Ki    FixedWingModeManager::control_auto_landing_circular()
  [NEW]    +696  [NEW]    +696    FixedWingModeManager::vehicle_attitude_poll()
  +0.4%    +624  +0.4%    +624    [section .text]
  [DEL]    -616  [DEL]    -616    NPFG::guideToPath()
  [DEL]    -632  [DEL]    -632    FixedwingPositionControl::parameters_update()
  [DEL]    -684  [DEL]    -684    FixedwingPositionControl::control_auto_position()
  [DEL]    -788  [DEL]    -788    FixedwingPositionControl::control_manual_position()
  [DEL]    -828  [DEL]    -828    FixedwingPositionControl::control_auto_loiter()
  [DEL]    -842  [DEL]    -842    FixedwingPositionControl::updateParamsImpl()
  [DEL] -1.39Ki  [DEL] -1.39Ki    FixedwingPositionControl::control_auto_landing_circular()
  [DEL] -1.57Ki  [DEL] -1.57Ki    FixedwingPositionControl::control_auto_landing_straight()
  [DEL] -1.64Ki  [DEL] -1.64Ki    FixedwingPositionControl::control_auto_takeoff()
  [DEL] -2.32Ki  [DEL] -2.32Ki    FixedwingPositionControl::Run()
  [DEL] -2.91Ki  [DEL] -2.91Ki    FixedwingPositionControl::FixedwingPositionControl()
+1.1%      +4  +1.1%      +4    .init_section
+0.7% +13.1Ki  [ = ]       0    .debug_abbrev
+0.5%    +824  [ = ]       0    .debug_aranges
+0.4% +1.69Ki  [ = ]       0    .debug_frame
+0.7%  +192Ki  [ = ]       0    .debug_info
+0.5% +24.2Ki  [ = ]       0    .debug_line
  [NEW]      +2  [ = ]       0    [Unmapped]
  +0.5% +24.2Ki  [ = ]       0    [section .debug_line]
+0.3% +9.57Ki  [ = ]       0    .debug_loclists
+0.1%    +372  [ = ]       0    .debug_rnglists
+0.3% +8.91Ki  [ = ]       0    .debug_str
-0.4%      -1  [ = ]       0    .shstrtab
+0.6% +3.85Ki  [ = ]       0    .strtab
  [NEW]     +74  [ = ]       0    AirspeedDirectionController::AirspeedDirectionController()
  [NEW]     +54  [ = ]       0    AirspeedDirectionController::controlHeading()
  [NEW]      +7  [ = ]       0    C.54.0
  [DEL]      -7  [ = ]       0    C.60.0
  [NEW]     +73  [ = ]       0    CombinedControllerConfigurationHandler::floatValueChanged()
  [NEW]     +68  [ = ]       0    CombinedControllerConfigurationHandler::resetLastPublishTime()
  [NEW]     +66  [ = ]       0    CombinedControllerConfigurationHandler::setClimbRateTarget()
  [NEW]     +78  [ = ]       0    CombinedControllerConfigurationHandler::setDisableUnderspeedProtection()
  [NEW]     +76  [ = ]       0    CombinedControllerConfigurationHandler::setEnforceLowHeightCondition()
  [NEW]     +66  [ = ]       0    CombinedControllerConfigurationHandler::setLateralAccelMax()
  [NEW]     +59  [ = ]       0    CombinedControllerConfigurationHandler::setPitchMax()
  [NEW]     +59  [ = ]       0    CombinedControllerConfigurationHandler::setPitchMin()
  [NEW]     +65  [ = ]       0    CombinedControllerConfigurationHandler::setSinkRateTarget()
  [NEW]     +62  [ = ]       0    CombinedControllerConfigurationHandler::setSpeedWeight()
  [NEW]     +62  [ = ]       0    CombinedControllerConfigurationHandler::setThrottleMax()
  [NEW]     +62  [ = ]       0    CombinedControllerConfigurationHandler::setThrottleMin()
  [NEW]     +53  [ = ]       0    CombinedControllerConfigurationHandler::update()
  [NEW]     +91  [ = ]       0    CourseToAirspeedRefMapper::getMinAirspeedForCurrentBearing()
  [NEW]     +81  [ = ]       0    CourseToAirspeedRefMapper::infeasibleAirVelRef()
  [NEW]     +93  [ = ]       0    CourseToAirspeedRefMapper::mapCourseSetpointToHeadingSetpoint()
 -95.8% +2.64Ki  [ = ]       0    [218 Others]
+0.4% +2.53Ki  [ = ]       0    .symtab
  [NEW]     +80  [ = ]       0    AirspeedDirectionController::AirspeedDirectionController()
  [NEW]     +32  [ = ]       0    AirspeedDirectionController::controlHeading()
  [NEW]     +32  [ = ]       0    C.54.0
  [DEL]     -32  [ = ]       0    C.60.0
  [NEW]     +48  [ = ]       0    CombinedControllerConfigurationHandler::floatValueChanged()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::resetLastPublishTime()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setClimbRateTarget()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setDisableUnderspeedProtection()
  [NEW]     +48  [ = ]       0    CombinedControllerConfigurationHandler::setEnforceLowHeightCondition()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setLateralAccelMax()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setPitchMax()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setPitchMin()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setSinkRateTarget()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setSpeedWeight()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setThrottleMax()
  [NEW]     +32  [ = ]       0    CombinedControllerConfigurationHandler::setThrottleMin()
  [NEW]     +48  [ = ]       0    CombinedControllerConfigurationHandler::update()
  [NEW]     +48  [ = ]       0    CourseToAirspeedRefMapper::getMinAirspeedForCurrentBearing()
  [NEW]     +48  [ = ]       0    CourseToAirspeedRefMapper::infeasibleAirVelRef()
  [NEW]     +16  [ = ]       0    CourseToAirspeedRefMapper::mapCourseSetpointToHeadingSetpoint()
 -95.6% +1.86Ki  [ = ]       0    [228 Others]
-5.5%    -428  [ = ]       0    [Unmapped]
+0.6%  +261Ki  +0.2% +4.42Ki    TOTAL

Updated: 2025-05-26T12:04:00

@RomanBapst RomanBapst force-pushed the pr-fw_ctrl_api branch 3 times, most recently from 4544dec to daa6b1a Compare January 8, 2025 12:40
Copy link
Contributor

@KonradRudin KonradRudin left a comment

Choose a reason for hiding this comment

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

I like the restructuring, having the fixed wing position control more separated into the mode and the actual control. As well as having more intermediate options.
I went through all of it. but not in the complete detail yet, just when i saw something i mentioned it.
Biggest issue for me is that we don't yet have a clear way to tell, that the longitudinal and lateral controller should be enabled or not. Should be in the vehicle control mode flags propably like _vcontrol_mode.flag_control_rates_enabled

Copy link
Member

@Jaeyoung-Lim Jaeyoung-Lim left a comment

Choose a reason for hiding this comment

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

Sorry that I am late to comment on this PR. I think there would be a lot of value of creating a FW API.

The api proposed have separate messages for longitudinal and lateral gudiance. This seems to be built on the assumption that lateral and longitudinal control (TECS) would be controlled in a decoupled way.

However, it would have been nicer if the api would be designed for more "generic" fixed-wing tasks, rather than exposing configurations of the underlying interface. IMO, an api should fully define what the vehicle "should" do for a given task (e.g. path following), rather than expose the underlying implementation.

  • Lateral/longitudinal controller decoupling is a design choice for a specific implementation. This would make it hard for other controllers to share the API, if the controllers do not have such decoupling (e.g. 3D NDI acceleration-based control).

  • The decoupling is not only not necessary for the task of path following, but can even limit what kind of paths we can follow in 3D. For example, if you try to track an inclined loiter(or any complex 3D path of arbitrary shape) the height rate setpoint in the FwLongitudinalSetpoint.msg is no longer usable, since the information on the 3D geometry is already lost (e.g. height rate depends on the speed and direction of the vehicle to stay on the path).

Is there a good reason that we want to enforce the separation of lateral/longitudinal control on the API side?
@tstastny

@RomanBapst
Copy link
Contributor Author

@Jaeyoung-Lim Thanks for your input on this!

The api proposed have separate messages for longitudinal and lateral gudiance. This seems to be built on the assumption that lateral and longitudinal control (TECS) would be controlled in a decoupled way.

Yes, and so far lateral and longitudinal control have almost completely been decoupled in PX4. The only coupling I am aware of is that NPFG used to be able to change the airspeed setpoint. But other than that, it was decoupled.
So far this architecture has brought us a long way and I don't think it's terrible.

However, it would have been nicer if the api would be designed for more "generic" fixed-wing tasks, rather than exposing configurations of the underlying interface. IMO, an api should fully define what the vehicle "should" do for a given task (e.g. path following), rather than expose the underlying implementation.

You are not limited to the exposed interfaces presented in this PR. If you want to have your fancy NDI controller running offboard and send attitude / rate or even actuator commands directly, you are free to do so, those interfaces I think are already there.

Lateral/longitudinal controller decoupling is a design choice for a specific implementation. This would make it hard for other controllers to share the API, if the controllers do not have such decoupling (e.g. 3D NDI acceleration-based control).

I think it's a design choice which solves 95% of the use case that people would want. I think that's pretty good.

The decoupling is not only not necessary for the task of path following, but can even limit what kind of paths we can follow in 3D. For example, if you try to track an inclined loiter(or any complex 3D path of arbitrary shape) the height rate setpoint in the FwLongitudinalSetpoint.msg is no longer usable, since the information on the 3D geometry is already lost (e.g. height rate depends on the speed and direction of the vehicle to stay on the path).

Could you please specify the exact interface that you would need to solve whatever use case you are trying to solve?
If it's a valid use case and it cannot be done with the current API, then we could always add it.

Generally, I have a feeling that your expectation is that ONE uorb topic defines exactly ONE control API. I don't think this needs to be true necessarily. I think you will use some kind of SDK, which will expose one interface to the developer, but the SDK itself can use multiple uorb topics.

@tstastny
Copy link

tstastny commented Feb 12, 2025

Hi. Thanks @RomanBapst and @KonradRudin for putting in work to finally start cleaning up the the fixed-wing high-level control infrastructure a bit! I haven't had time to fully go through the details, but I am a little confused what specifically is the "API" here. But there may just be some difference in everyone's semantics...

The uorb topics in the figure look more like logging topics to me, as I find it odd an application would send e.g. pitch setpoint, throttle setpoint, altitude setpoint, and height rate setpoint all out into the ether at the same time? Maybe @RomanBapst you can de-confuse me on the strategy? :) Are there multiple uorbs being bundled and sent at once from e.g. the ROS2 mode? Are these messages just defining what each block (controller) needs as input? And the actual exposed API will be something more basic, with each control block parsing it to convert to the right inputs to each? Maybe it would help to include the module boundaries on the diagram, so it's clear where uorbs are subscribed to, vs whatever internal parsing a module does to input the right args to the control libraries.

On the topic of alternate APIs (@Jaeyoung-Lim ), the block diagram itself looks as though it's not terribly far away from supporting a wide array of things. e.g. if there were a single 3d instantaneous path setpoint API, the height component of it could still be routed to Alt-Ctrl, the vertical incline of the path then converted to a height rate setpoint that could be used as feedforward, added to the feedback height rate from Alt-Ctrl, and then sent off to TECS (or Velocity NDI, or whatever). It looks as though that is actually already somewhat happening in the diagram?

So long as the blocks on the diagram are decoupled as shown, and new urobs can be made with a parser to spit out the resp. input msgs each controller one is using needs, I would imagine it's possible to do, right? Or maybe I miss something on the routing details? (I am a bit foggy on things now after not looking for a long time)

@RomanBapst RomanBapst changed the title WIP: Fixed wing control API WIP: Fixed wing control refactoring Feb 13, 2025
@RomanBapst
Copy link
Contributor Author

The uorb topics in the figure look more like logging topics to me, as I find it odd an application would send e.g. pitch setpoint, throttle setpoint, altitude setpoint, and height rate setpoint all out into the ether at the same time? Maybe @RomanBapst you can de-confuse me on the strategy? :)

@tstastny I have changed the title of the PR to not contain the word API, as it seems to be confusing.
You can call the new uorb messages an API, but it's definitely not the API we want to expose 1 to 1 to the end developer.
The idea would be that the SDK which is used for development (auterion SDK or whatever SDK you like), converts the developer facing controller setpoint into the uorb messages defined in this PR.

Also note, that the current uorb messages contain certain fields I wish would not be there, but since it was a priority to not break existing functionality with this refactor, I added them regardless. I am all in favor to remove fields like heading_sp_runway_takeoff and pitch_sp from the message.
It's the fixed wing takeoff and the fixed wing landing modes which requires these fields.

I'm also adding a diagram here which I hope explains a bit better the architecture in terms of modularity.
image

@PX4 PX4 deleted a comment from github-actions bot May 20, 2025
@sfuhrer
Copy link
Contributor

sfuhrer commented May 22, 2025

@RomanBapst @mahima-yoga @KonradRudin I've cleaned up the commits (incl. incorporating the changes in #24886) and force pushed.

Edit: now also rebased on main to hopefully get rid of the MAVROS CI failures.

@PX4 PX4 deleted a comment from github-actions bot May 22, 2025
@PX4 PX4 deleted a comment from github-actions bot May 22, 2025
@sfuhrer sfuhrer force-pushed the pr-fw_ctrl_api branch 2 times, most recently from 9db1ee4 to 395a3bd Compare May 22, 2025 14:12
@PX4 PX4 deleted a comment from github-actions bot May 22, 2025
RomanBapst and others added 12 commits May 26, 2025 11:13
- split up old module into two, one handling setpoint generation, one control
- add lateral and longitudinal control setpoints topics that can also be
injected from companion computer
- add configuration topics that (optionally) configure the controller
with limits and momentary settings

Signed-off-by: RomanBapst <bapstroman@gmail.com>
Signed-off-by: Silvan <silvan@auterion.com>
…_wheel

Signed-off-by: Silvan <silvan@auterion.com>
Signed-off-by: Silvan <silvan@auterion.com>
…o min tas

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Params that are used by FW Mode Manager
- FW NPFG: NPFG params, should be renamed to FW Lateral Control once moved to the lat/lon controller
- FW Auto Takeoff
- FW Auto Landing

Params used by Fw Lat/Long Controller:
- FW Lateral Control
- FW Longitudinal Control

Params used by both:
- FW General

Params used by Performance model:
- FW Performance (could be moerged with FW General?)

Signed-off-by: Silvan <silvan@auterion.com>
add RunwayControl messge to pass wheel steering controls to wheel controller

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

Runway takeoff: specify that RWTO_TKOFF is directly applied during takeoff

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

msg/RateCtrlStatus: remove unused wheel_rate_integ field

The wheel rate controller is not run in the moduels that are now
running the MC/FW rate controllers, so thsi field canot be filled.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

wheel rate controller: use speed scaler quadratically on integrator

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

wheel yaw controller: use a time constant of 0.1

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

FW Attitude Controller: lock heading setpoint for wheels to initial heading

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
…ight rate change

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan <silvan@auterion.com>
- Add versioning to interfacing messages
- Add header description
- Add units, frame and range wherever possible
- Add [norm] and @range indentifiers
Signed-off-by: Silvan <silvan@auterion.com>
@PX4 PX4 deleted a comment from github-actions bot May 26, 2025
@sfuhrer
Copy link
Contributor

sfuhrer commented May 26, 2025

I'm going ahead and merge this, after giving this a lot of testing in the last months. Wrapping up the final documentation items in separate PRs.
Great work everybody!

@sfuhrer sfuhrer merged commit ea94bc1 into main May 26, 2025
73 of 74 checks passed
@sfuhrer sfuhrer deleted the pr-fw_ctrl_api branch May 26, 2025 12:47
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

8 participants