Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Add IC engine control module #24055

Open
wants to merge 11 commits into
base: main
Choose a base branch
from
Open

Add IC engine control module #24055

wants to merge 11 commits into from

Conversation

sfuhrer
Copy link
Contributor

@sfuhrer sfuhrer commented Nov 29, 2024

The RPM based functionality requires #24041

Solved Problem

Adding fuel engine support to PX4, including:

  • starting logic
  • RPM based re-start logic
  • expose actuators as functions

Solution

Adding now module to handle ICE acutators. It gets fed by user inputs (for now manual control) and actuator_motors (TODO: add identifier which actuator_motor instances are fuel engines), and outputs the 4 fuel engine actuators: ignition, throttle, choke, starter motor.

A flow chart of the solution:
Screenshot from 2025-02-07 09-25-14

The proposed state machine:
Screenshot from 2025-02-06 14-39-13

Changelog Entry

For release notes:

Feature: Add IC engine control module

Alternatives / Follow-ups

Couple of ideas for followup work:

Test coverage

Tested on bench.

Context

Note: This feature is not enabled by default and needs to be configured together with the rpm capture driver: CONFIG_MODULES_INTERNAL_COMBUSTION_ENGINE_CONTROL=y
CONFIG_DRIVERS_RPM_CAPTURE=y

image

Below is a plot from the test bench:
Screenshot from 2025-02-06 12-07-44
During the starting and running state there was a fault and ICE control was able to recover.

@sfuhrer sfuhrer requested a review from RomanBapst November 29, 2024 10:22
Copy link

github-actions bot commented Nov 29, 2024

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 712 byte (0.03 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%    +648  +0.0%    +648    .text
  +3.9%    +268  +3.9%    +268    ../../src/lib/mixer_module/mixer_module.cpp
  +0.1%    +190  +0.1%    +190    ROMFS/nsh_romfsimg.c
  +0.1%    +166  +0.1%    +166    [section .text]
  +0.4%     +20  +0.4%     +20    ../../src/modules/logger/logged_topics.cpp
  [NEW]     +16  [NEW]     +16    msg/topics_sources/internal_combustion_engine_control.cpp
  +0.2%      +4  +0.2%      +4    ../../platforms/common/uORB/uORBDeviceMaster.cpp
  +0.1%      +4  +0.1%      +4    ../../src/modules/mag_bias_estimator/MagBiasEstimator.cpp
  -2.6%      -4  -2.6%      -4    ../../platforms/common/uORB/Subscription.cpp
  -0.2%      -4  -0.2%      -4    ../../src/lib/geo/geo.cpp
  -3.4%      -4  -3.4%      -4    stdlib/lib_srand.c
  -0.6%      -8  -0.6%      -8    ../../platforms/common/uORB/uORBManager.cpp
[ = ]       0  +0.1%     +64    .bss
  [ = ]       0  +6.8%     +52    [section .bss]
  [ = ]       0  +8.8%     +12    ../../src/lib/mixer_module/mixer_module.cpp
  [ = ]       0  +3.1%      +4    chip/stm32_exti_gpio.c
  [ = ]       0  -0.1%      -4    ../../platforms/nuttx/src/px4/common/board_dma_alloc.c
+0.0%    +972  [ = ]       0    .debug_abbrev
  +0.5%     +16  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
   +11%     +56  [ = ]       0    ../../src/lib/version/version.c
  [NEW]    +900  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
+0.0%     +64  [ = ]       0    .debug_aranges
  +4.8%     +40  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -5.0%      -8  [ = ]       0    ../../src/lib/version/version.c
  [NEW]     +32  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
+0.0%    +176  [ = ]       0    .debug_frame
+0.1% +15.5Ki  [ = ]       0    .debug_info
  +0.1%      +7  [ = ]       0    ../../platforms/common/uORB/Subscription.cpp
  +0.1%      +7  [ = ]       0    ../../platforms/common/uORB/SubscriptionInterval.cpp
  +0.0%      +7  [ = ]       0    ../../platforms/common/uORB/uORB.cpp
  +0.0%      +7  [ = ]       0    ../../platforms/common/uORB/uORBDeviceMaster.cpp
  +0.0%      +7  [ = ]       0    ../../platforms/common/uORB/uORBDeviceNode.cpp
  +0.0%      +7  [ = ]       0    ../../platforms/common/uORB/uORBManager.cpp
  +0.0%      +7  [ = ]       0    ../../platforms/nuttx/src/px4/common/gpio/mcp23009/mcp23009.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/adc/ads1115/ads1115_main.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/adc/board_adc/ADC.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/barometer/bmp388/bmp388.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/barometer/ms5611/ms5611.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/camera_capture/camera_capture.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/camera_trigger/camera_trigger.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/cdcacm_autostart/cdcacm_autostart.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/differential_pressure/ms4525do/MS4525DO.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/differential_pressure/ms5525dso/MS5525DSO.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/differential_pressure/sdp3x/SDP3X.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/distance_sensor/cm8jl65/CM8JL65.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/distance_sensor/lightware_laser_serial/lightware_laser_serial.cpp
 -99.9% +15.3Ki  [ = ]       0    [478 Others]
+0.0% +2.23Ki  [ = ]       0    .debug_line
  -0.5%      -8  [ = ]       0    ../../platforms/common/uORB/Subscription.cpp
  -0.4%     -16  [ = ]       0    ../../platforms/common/uORB/uORBManager.cpp
  +0.3%     +38  [ = ]       0    ../../src/drivers/dshot/DShot.cpp
  +0.6%     +38  [ = ]       0    ../../src/drivers/pwm_out/PWMOut.cpp
  +0.3%     +40  [ = ]       0    ../../src/drivers/px4io/px4io.cpp
  +0.4%     +40  [ = ]       0    ../../src/drivers/uavcan/actuators/esc.cpp
  +0.6%     +40  [ = ]       0    ../../src/drivers/uavcan/actuators/servo.cpp
  +0.0%     +40  [ = ]       0    ../../src/drivers/uavcan/uavcan_main.cpp
  +0.1%     +40  [ = ]       0    ../../src/drivers/uavcan/uavcan_servers.cpp
  +3.5%    +597  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -1.3%     -25  [ = ]       0    ../../src/lib/version/version.c
  +0.3%     +21  [ = ]       0    ../../src/modules/logger/logged_topics.cpp
  +0.7%     +38  [ = ]       0    ../../src/modules/simulation/pwm_out_sim/PWMSim.cpp
  [NEW] +1.33Ki  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
  +0.7%     +40  [ = ]       0    msg/topics_sources/uORBTopics.cpp
+0.0%    +875  [ = ]       0    .debug_loc
  -0.4%     -15  [ = ]       0    ../../src/drivers/adc/board_adc/ADC.cpp
  -0.1%     -15  [ = ]       0    ../../src/drivers/px4io/px4io.cpp
  +0.0%     +30  [ = ]       0    ../../src/drivers/uavcan/uavcan_servers.cpp
  +4.0%    +712  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  +0.2%     +15  [ = ]       0    ../../src/lib/rtl/rtl_time_estimator.cpp
  -0.2%     -13  [ = ]       0    ../../src/lib/weather_vane/WeatherVane.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/airspeed_selector/airspeed_selector_main.cpp
  -0.4%     -15  [ = ]       0    ../../src/modules/commander/HealthAndArmingChecks/checks/accelerometerCheck.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/commander/failure_detector/FailureDetector.cpp
  +0.2%     +15  [ = ]       0    ../../src/modules/flight_mode_manager/FlightModeManager.cpp
  +0.0%     +15  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp
  +0.3%     +15  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp
  +0.2%     +15  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Transition/FlightTaskTransition.cpp
  +0.2%     +15  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Utility/Sticks.cpp
  -0.1%     -64  [ = ]       0    ../../src/modules/fw_pos_control/FixedwingPositionControl.cpp
  +0.0%     +15  [ = ]       0    ../../src/modules/fw_rate_control/FixedwingRateControl.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/gimbal/output.cpp
  -0.2%     -15  [ = ]       0    ../../src/modules/land_detector/LandDetector.cpp
  +0.9%     +91  [ = ]       0    ../../src/modules/logger/logged_topics.cpp
  -0.0%     -15  [ = ]       0    ../../src/modules/mc_pos_control/MulticopterPositionControl.cpp
 -100.0%    +134  [ = ]       0    [9 Others]
+0.0%    +217  [ = ]       0    .debug_ranges
  +3.3%    +208  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -2.6%      -8  [ = ]       0    ../../src/lib/version/version.c
  [NEW]     +16  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
  +1.6%      +1  [ = ]       0    task/task_cancelpt.c
+0.0%    +744  [ = ]       0    .debug_str
  +0.1%     +58  [ = ]       0    
  +0.2%     +35  [ = ]       0    ../../src/drivers/adc/ads1115/ads1115_main.cpp
  +0.4%     +78  [ = ]       0    ../../src/drivers/dshot/DShot.cpp
  +6.1%    +528  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  +0.5%      +8  [ = ]       0    ../../src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessMCTilt.cpp
  [NEW]     +37  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
-0.5%      -1  [ = ]       0    .shstrtab
+0.0%    +337  [ = ]       0    .strtab
  +5.3%    +232  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -8.1%     -32  [ = ]       0    ../../src/lib/version/version.c
  +0.1%     +96  [ = ]       0    [section .strtab]
  [NEW]     +41  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
+0.1%    +320  [ = ]       0    .symtab
  +1.3%     +16  [ = ]       0    ../../src/drivers/rc/dsm_rc/DsmRc.cpp
  +5.5%    +224  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -7.0%     -64  [ = ]       0    ../../src/lib/version/version.c
  +0.3%     +16  [ = ]       0    ../../src/modules/fw_pos_control/FixedwingPositionControl.cpp
  +0.1%     +80  [ = ]       0    [section .symtab]
  [NEW]     +48  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
-5.4%    -648  [ = ]       0    [Unmapped]
+0.0% +21.3Ki  +0.0%    +712    TOTAL

px4_fmu-v6x [Total VM Diff: 688 byte (0.03 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%    +624  +0.0%    +624    .text
  +3.9%    +268  +3.9%    +268    ../../src/lib/mixer_module/mixer_module.cpp
  +0.1%    +169  +0.1%    +169    [section .text]
  +0.1%    +159  +0.1%    +159    ROMFS/nsh_romfsimg.c
  +0.4%     +20  +0.4%     +20    ../../src/modules/logger/logged_topics.cpp
  [NEW]     +16  [NEW]     +16    msg/topics_sources/internal_combustion_engine_control.cpp
  +0.2%      +4  +0.2%      +4    ../../platforms/common/uORB/uORBDeviceMaster.cpp
  +0.1%      +4  +0.1%      +4    ../../src/modules/mag_bias_estimator/MagBiasEstimator.cpp
  -2.6%      -4  -2.6%      -4    ../../platforms/common/uORB/Subscription.cpp
  -0.1%      -4  -0.1%      -4    ../../src/drivers/uavcan/uavcan_drivers/stm32h7/driver/src/uc_stm32h7_can.cpp
  -0.6%      -8  -0.6%      -8    ../../platforms/common/uORB/uORBManager.cpp
[ = ]       0  +0.1%     +64    .bss
  [ = ]       0  +6.9%     +60    [section .bss]
  [ = ]       0  +9.1%     +12    ../../src/lib/mixer_module/mixer_module.cpp
  [ = ]       0  -0.1%      -4    ../../platforms/nuttx/src/px4/common/board_dma_alloc.c
  [ = ]       0  -3.1%      -4    ../../src/drivers/uavcan/uavcan_drivers/stm32h7/driver/src/uc_stm32h7_clock.cpp
+0.0%    +972  [ = ]       0    .debug_abbrev
  +0.5%     +16  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
   +11%     +56  [ = ]       0    ../../src/lib/version/version.c
  [NEW]    +900  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
+0.0%     +64  [ = ]       0    .debug_aranges
  +4.8%     +40  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -5.0%      -8  [ = ]       0    ../../src/lib/version/version.c
  [NEW]     +32  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
+0.0%    +176  [ = ]       0    .debug_frame
+0.1% +15.3Ki  [ = ]       0    .debug_info
  +0.1%      +7  [ = ]       0    ../../platforms/common/uORB/Subscription.cpp
  +0.1%      +7  [ = ]       0    ../../platforms/common/uORB/SubscriptionInterval.cpp
  +0.0%      +7  [ = ]       0    ../../platforms/common/uORB/uORB.cpp
  +0.0%      +7  [ = ]       0    ../../platforms/common/uORB/uORBDeviceMaster.cpp
  +0.0%      +7  [ = ]       0    ../../platforms/common/uORB/uORBDeviceNode.cpp
  +0.0%      +7  [ = ]       0    ../../platforms/common/uORB/uORBManager.cpp
  +0.0%      +7  [ = ]       0    ../../platforms/nuttx/src/px4/common/gpio/mcp23009/mcp23009.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/adc/ads1115/ads1115_main.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/adc/board_adc/ADC.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/barometer/bmp388/bmp388.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/barometer/invensense/icp201xx/ICP201XX.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/barometer/ms5611/ms5611.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/camera_capture/camera_capture.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/camera_trigger/camera_trigger.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/cdcacm_autostart/cdcacm_autostart.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/differential_pressure/ms4525do/MS4525DO.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/differential_pressure/ms5525dso/MS5525DSO.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/differential_pressure/sdp3x/SDP3X.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/distance_sensor/cm8jl65/CM8JL65.cpp
  +0.0%      +7  [ = ]       0    ../../src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp
 -99.9% +15.2Ki  [ = ]       0    [462 Others]
+0.0% +2.19Ki  [ = ]       0    .debug_line
  -0.5%      -8  [ = ]       0    ../../platforms/common/uORB/Subscription.cpp
  -0.4%     -16  [ = ]       0    ../../platforms/common/uORB/uORBManager.cpp
  +0.3%     +38  [ = ]       0    ../../src/drivers/dshot/DShot.cpp
  +0.6%     +38  [ = ]       0    ../../src/drivers/pwm_out/PWMOut.cpp
  +0.3%     +40  [ = ]       0    ../../src/drivers/px4io/px4io.cpp
  +0.4%     +40  [ = ]       0    ../../src/drivers/uavcan/actuators/esc.cpp
  +0.6%     +40  [ = ]       0    ../../src/drivers/uavcan/actuators/servo.cpp
  +0.0%     +40  [ = ]       0    ../../src/drivers/uavcan/uavcan_main.cpp
  +0.1%     +40  [ = ]       0    ../../src/drivers/uavcan/uavcan_servers.cpp
  +3.5%    +597  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -1.3%     -25  [ = ]       0    ../../src/lib/version/version.c
  +0.3%     +21  [ = ]       0    ../../src/modules/logger/logged_topics.cpp
  [NEW] +1.33Ki  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
  +0.7%     +40  [ = ]       0    msg/topics_sources/uORBTopics.cpp
  -0.3%      -3  [ = ]       0    task/task_cancelpt.c
+0.0%    +910  [ = ]       0    .debug_loc
  +0.4%     +15  [ = ]       0    ../../src/drivers/adc/board_adc/ADC.cpp
  -0.2%     -15  [ = ]       0    ../../src/drivers/camera_trigger/camera_trigger.cpp
  +0.2%     +15  [ = ]       0    ../../src/drivers/osd/msp_osd/msp_osd.cpp
  +0.3%     +13  [ = ]       0    ../../src/drivers/rc_input/crsf_telemetry.cpp
  +1.2%     +13  [ = ]       0    ../../src/drivers/rc_input/ghst_telemetry.cpp
  -0.0%     -15  [ = ]       0    ../../src/drivers/uavcan/uavcan_main.cpp
  -0.0%     -27  [ = ]       0    ../../src/drivers/uavcan/uavcan_servers.cpp
  +4.1%    +727  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  +0.1%     +15  [ = ]       0    ../../src/modules/airspeed_selector/airspeed_selector_main.cpp
  -0.2%     -15  [ = ]       0    ../../src/modules/commander/HealthAndArmingChecks/checks/magnetometerCheck.cpp
  +0.3%     +15  [ = ]       0    ../../src/modules/commander/HomePosition.cpp
  +0.0%     +15  [ = ]       0    ../../src/modules/commander/accelerometer_calibration.cpp
  +1.1%     +15  [ = ]       0    ../../src/modules/events/status_display.cpp
  -0.0%     -13  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/AutoFollowTarget/FlightTaskAutoFollowTarget.cpp
  -0.0%     -13  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp
  +0.1%     +15  [ = ]       0    ../../src/modules/fw_att_control/FixedwingAttitudeControl.cpp
  -0.1%     -64  [ = ]       0    ../../src/modules/fw_pos_control/FixedwingPositionControl.cpp
  -0.0%     -15  [ = ]       0    ../../src/modules/fw_rate_control/FixedwingRateControl.cpp
  +0.9%     +91  [ = ]       0    ../../src/modules/logger/logged_topics.cpp
  +0.0%     +15  [ = ]       0    ../../src/modules/mc_pos_control/MulticopterPositionControl.cpp
 -100.0%    +123  [ = ]       0    [9 Others]
+0.0%    +218  [ = ]       0    .debug_ranges
  +3.3%    +208  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -2.6%      -8  [ = ]       0    ../../src/lib/version/version.c
  [NEW]     +16  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
  +3.1%      +2  [ = ]       0    task/task_cancelpt.c
+0.0%    +744  [ = ]       0    .debug_str
  +0.1%     +58  [ = ]       0    
  +0.2%     +35  [ = ]       0    ../../src/drivers/adc/ads1115/ads1115_main.cpp
  +0.4%     +78  [ = ]       0    ../../src/drivers/dshot/DShot.cpp
  +6.1%    +536  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  [NEW]     +37  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
+1.4%      +3  [ = ]       0    .shstrtab
+0.1%    +337  [ = ]       0    .strtab
  +5.3%    +232  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -8.1%     -32  [ = ]       0    ../../src/lib/version/version.c
  +0.1%     +96  [ = ]       0    [section .strtab]
  [NEW]     +41  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
+0.1%    +320  [ = ]       0    .symtab
  +1.7%     +16  [ = ]       0    ../../src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c.cpp
  +5.4%    +224  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  -7.0%     -64  [ = ]       0    ../../src/lib/version/version.c
  +0.3%     +16  [ = ]       0    ../../src/modules/fw_pos_control/FixedwingPositionControl.cpp
  +0.1%     +80  [ = ]       0    [section .symtab]
  [NEW]     +48  [ = ]       0    msg/topics_sources/internal_combustion_engine_control.cpp
-0.9%    -624  [ = ]       0    [Unmapped]
+0.0% +21.2Ki  +0.0%    +688    TOTAL

Updated: 2025-02-07T09:29:08

@RomanBapst RomanBapst requested review from KonradRudin and removed request for KonradRudin November 29, 2024 15:21
@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/gas-engine/42729/9

@github-actions github-actions bot added the stale label Jan 9, 2025
Copy link
Contributor

@Perrrewi Perrrewi left a comment

Choose a reason for hiding this comment

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

I made some comments, but in general it looks good to me

@Perrrewi Perrrewi force-pushed the pr-ice-control-module-main branch 2 times, most recently from 8eb6dfb to 00375b9 Compare February 5, 2025 12:21
@Perrrewi Perrrewi force-pushed the pr-ice-control-module-main branch from d810d24 to c5f8416 Compare February 7, 2025 09:23
@sfuhrer sfuhrer changed the title [WIP] Add IC engine control module Add IC engine control module Feb 7, 2025
Copy link
Contributor Author

@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.

Beside the small comments I would have one "feature" request: To add a 1s delay between the starting retries. That should help to reduce wear on the starter motor and makes the starter retries audibly distinguishable from each other.

if param compare -s ICE_EN 1
then
internal_combustion_engine_control start
echo "****INFO [init] Internal Combustion Engine Control started"
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Suggested change
echo "****INFO [init] Internal Combustion Engine Control started"

This is a left over from debugging.

@@ -81,3 +81,5 @@ CONFIG_EXAMPLES_PX4_MAVLINK_DEBUG=y
CONFIG_EXAMPLES_PX4_SIMPLE_APP=y
CONFIG_EXAMPLES_WORK_ITEM=y
CONFIG_MODULES_SPACECRAFT=n

CONFIG_MODULES_INTERNAL_COMBUSTION_ENGINE_CONTROL=y
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Suggested change
CONFIG_MODULES_INTERNAL_COMBUSTION_ENGINE_CONTROL=y

This was also just for testing.

float32 choke_control # [0,1]
float32 starter_engine_control # [0,1]

uint8 user_request # user intent for on/off/keep
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Suggested change
uint8 user_request # user intent for on/off/keep
uint8 user_request # user intent for on/off

I don't think the keep is implemented, is it?

static_assert(num_data_points == (int)OutputFunction::IC_Engine_Starter - (int)OutputFunction::IC_Engine_Ignition + 1,
"number of functions mismatch");

uORB::Subscription _topic{ORB_ID(internal_combustion_engine_control)};
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Suggested change
uORB::Subscription _topic{ORB_ID(internal_combustion_engine_control)};
uORB::Subscription _internal_combustion_engine_control_sub{ORB_ID(internal_combustion_engine_control)};

values:
0: No activation
1: On arming - disarming
2: Mavlink?
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Suggested change
2: Mavlink?
2: Mavlink - TODO

short: Apply choke when stopping engine
long: TBD
type: boolean
default: false
Copy link
Contributor Author

Choose a reason for hiding this comment

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

I would change the default to true.

short: Try to re-start engine if it stops
long: TBD
type: boolean
default: false
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Suggested change
default: false
default: true

max: 10
decimal: 1
increment: 0.1
default: 1
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Suggested change
default: 1
default: 0

ICE_IGN_DELAY:
description:
short: Cold-start delay after ignition before engaging starter
long: TBD
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Suggested change
long: TBD
long: In case that the ignition takes a moment to be up and running, this parameter can be set to account for that.


if (user_request == UserOnOffRequest::On && !_engine_tried_to_restart) {
_state = State::Starting;
instantiateEngineStart();
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Suggested change
instantiateEngineStart();
_state_start_time = now;

This method isn't needed anymore I would say.

And just store now at the beginning of the Run() function.

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