diff --git a/.github/workflows/mavros_tests.yml b/.github/workflows/mavros_tests.yml deleted file mode 100644 index b8df2541d8..0000000000 --- a/.github/workflows/mavros_tests.yml +++ /dev/null @@ -1,73 +0,0 @@ -name: MAVROS Tests - -on: - push: - branches: - - 'main' - paths-ignore: - - 'docs/**' - pull_request: - branches: - - '**' - paths-ignore: - - 'docs/**' - -concurrency: - group: ${{ github.workflow }}-${{ github.ref }} - cancel-in-progress: true - -jobs: - test: - name: "MAVROS ${{ matrix.config.name }}" - runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache] - permissions: - contents: read - container: - image: px4io/px4-dev-ros-noetic:2021-09-08 - env: - PX4_SBOM_DISABLE: 1 - strategy: - fail-fast: false - matrix: - config: - - {name: "Mission", test_file: "mavros_posix_test_mission.test", params: "mission:=MC_mission_box vehicle:=iris"} - - {name: "Offboard", test_file: "mavros_posix_tests_offboard_posctl.test", params: "vehicle:=iris"} - steps: - - uses: runs-on/action@v2 - - uses: actions/checkout@v6 - with: - fetch-depth: 1 - - name: Configure Git Safe Directory - run: git config --system --add safe.directory '*' - - - name: Setup - Install Python Test Dependencies - run: pip3 install -r Tools/setup/requirements.txt - - - uses: ./.github/actions/setup-ccache - id: ccache - with: - cache-key-prefix: ccache-sitl-gazebo-classic - max-size: 350M - - - uses: ./.github/actions/build-gazebo-sitl - - - name: Test - MAVROS ${{ matrix.config.name }} - run: | - ./test/rostest_px4_run.sh \ - ${{ matrix.config.test_file }} \ - ${{ matrix.config.params }} - timeout-minutes: 10 - - - uses: ./.github/actions/save-ccache - if: always() - with: - cache-primary-key: ${{ steps.ccache.outputs.cache-primary-key }} - - - name: Upload - Failed Test Logs - if: failure() - uses: actions/upload-artifact@v7 - with: - name: failed-mavros-${{ matrix.config.name }}-logs.zip - path: | - logs/**/**/**/*.log - logs/**/**/**/*.ulg diff --git a/.github/workflows/ros_integration_tests.yml b/.github/workflows/ros_integration_tests.yml index 14ac57cc97..c23fd7d9a8 100644 --- a/.github/workflows/ros_integration_tests.yml +++ b/.github/workflows/ros_integration_tests.yml @@ -121,7 +121,10 @@ jobs: shell: bash run: | . /opt/px4_ws/install/setup.bash - /opt/Micro-XRCE-DDS-Agent/build/MicroXRCEAgent udp4 localhost -p 8888 -v 0 & + # The Agent is started (and restarted between tests) by ros_test_runner.py + # so DDS graph state from a previous PX4 instance does not leak into the + # next test. Make the Agent binary discoverable on PATH. + export PATH="/opt/Micro-XRCE-DDS-Agent/build:$PATH" test/ros_test_runner.py --verbose --model iris --force-color timeout-minutes: 45 diff --git a/ROMFS/px4fmu_common/init.d/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/CMakeLists.txt index 3c6cfb13f9..dda7a9bad6 100644 --- a/ROMFS/px4fmu_common/init.d/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/CMakeLists.txt @@ -71,6 +71,7 @@ endif() if(CONFIG_MODULES_ROVER_DIFFERENTIAL) px4_add_romfs_files( + rc.rover rc.rover_differential_apps rc.rover_differential_defaults ) @@ -78,6 +79,7 @@ endif() if(CONFIG_MODULES_ROVER_ACKERMANN) px4_add_romfs_files( + rc.rover rc.rover_ackermann_apps rc.rover_ackermann_defaults ) @@ -92,6 +94,7 @@ endif() if(CONFIG_MODULES_ROVER_MECANUM) px4_add_romfs_files( + rc.rover rc.rover_mecanum_apps rc.rover_mecanum_defaults ) diff --git a/ROMFS/px4fmu_common/init.d/rc.rover b/ROMFS/px4fmu_common/init.d/rc.rover new file mode 100644 index 0000000000..acdc411713 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.rover @@ -0,0 +1,10 @@ +#!/bin/sh +# Standard apps for all rovers. + +# Start Land Detector. +land_detector start rover + +if param compare HIWONDER_EMM_EN 1 +then + hiwonder_emm start +fi diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps index 181233babe..a91275d44a 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps +++ b/ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps @@ -1,8 +1,7 @@ #!/bin/sh # Standard apps for an ackermann rover. +. ${R}etc/init.d/rc.rover + # Start rover ackermann module. rover_ackermann start - -# Start Land Detector. -land_detector start rover diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps b/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps index e1a7ecd9cc..2f16c23bc0 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps +++ b/ROMFS/px4fmu_common/init.d/rc.rover_differential_apps @@ -1,8 +1,7 @@ #!/bin/sh # Standard apps for a differential rover. +. ${R}etc/init.d/rc.rover + # Start rover differential module. rover_differential start - -# Start Land Detector. -land_detector start rover diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_mecanum_apps b/ROMFS/px4fmu_common/init.d/rc.rover_mecanum_apps index 77b131c984..7e80d9824c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_mecanum_apps +++ b/ROMFS/px4fmu_common/init.d/rc.rover_mecanum_apps @@ -1,8 +1,7 @@ #!/bin/sh # Standard apps for a mecanum drive rover. +. ${R}etc/init.d/rc.rover + # Start rover mecanum drive controller. rover_mecanum start - -# Start Land Detector. -land_detector start rover diff --git a/Tools/kconfig/allyesconfig.py b/Tools/kconfig/allyesconfig.py index a7398a5427..bd3fbe4f98 100644 --- a/Tools/kconfig/allyesconfig.py +++ b/Tools/kconfig/allyesconfig.py @@ -66,6 +66,7 @@ exception_list_sitl = [ 'COMMON_DISTANCE_SENSOR', # Fails I2C dependencies 'DRIVERS_DISTANCE_SENSOR', # Fails I2C dependencies 'COMMON_HYGROMETERS', # Fails I2C dependencies + 'DRIVERS_HIWONDER_EMM', # Fails I2C dependencies 'DRIVERS_HYGROMETER', # Fails I2C dependencies 'COMMON_IMU', # Fails I2C dependencies 'DRIVERS_IMU', # Fails I2C dependencies diff --git a/boards/ark/fmu-v6x/rover.px4board b/boards/ark/fmu-v6x/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/ark/fmu-v6x/rover.px4board +++ b/boards/ark/fmu-v6x/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/ark/fpv/rover.px4board b/boards/ark/fpv/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/ark/fpv/rover.px4board +++ b/boards/ark/fpv/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/ark/pi6x/rover.px4board b/boards/ark/pi6x/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/ark/pi6x/rover.px4board +++ b/boards/ark/pi6x/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/auterion/fmu-v6s/init/rc.board_defaults b/boards/auterion/fmu-v6s/init/rc.board_defaults index 1efbfc3811..517cd8ed32 100644 --- a/boards/auterion/fmu-v6s/init/rc.board_defaults +++ b/boards/auterion/fmu-v6s/init/rc.board_defaults @@ -9,6 +9,8 @@ param set-default SYS_DM_BACKEND 1 param set-default MAV_0_CONFIG 0 # Disable logger writing to FRAM, only stream over MAVLINK param set-default SDLOG_BACKEND 2 +# Disable UAVCAN tracing +param set-default UAVCAN_TRACE_EN 0 # 200kOhm/10kOhm voltage divider on V_BAT param set-default BAT1_V_DIV 21 diff --git a/boards/auterion/fmu-v6s/init/rc.board_sensors b/boards/auterion/fmu-v6s/init/rc.board_sensors index 9b48e805e6..961d975c90 100644 --- a/boards/auterion/fmu-v6s/init/rc.board_sensors +++ b/boards/auterion/fmu-v6s/init/rc.board_sensors @@ -37,7 +37,6 @@ then set INA_CONFIGURED yes fi - if param compare SENS_EN_INA228 1 then # Start Digital power monitors diff --git a/boards/auterion/fmu-v6s/rover.px4board b/boards/auterion/fmu-v6s/rover.px4board index 52d414fd50..d9bfec2d68 100644 --- a/boards/auterion/fmu-v6s/rover.px4board +++ b/boards/auterion/fmu-v6s/rover.px4board @@ -5,12 +5,14 @@ CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n -CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n CONFIG_MODULES_MC_ATT_CONTROL=n CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n -# CONFIG_EKF2_WIND is not set -CONFIG_MODULES_DIFFERENTIAL_DRIVE=y +CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y +CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y +CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/auterion/fmu-v6x/default.px4board b/boards/auterion/fmu-v6x/default.px4board index 1cef7804ab..4fcba9a10a 100644 --- a/boards/auterion/fmu-v6x/default.px4board +++ b/boards/auterion/fmu-v6x/default.px4board @@ -75,7 +75,6 @@ CONFIG_MODULES_NAVIGATOR=y CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_MECANUM=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y @@ -94,7 +93,6 @@ CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y -CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y CONFIG_SYSTEMCMDS_TUNE_CONTROL=y diff --git a/boards/auterion/fmu-v6x/rover.px4board b/boards/auterion/fmu-v6x/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/auterion/fmu-v6x/rover.px4board +++ b/boards/auterion/fmu-v6x/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/hkust/nxt-v1/default.px4board b/boards/hkust/nxt-v1/default.px4board index e301d641c5..5ab4f337fe 100644 --- a/boards/hkust/nxt-v1/default.px4board +++ b/boards/hkust/nxt-v1/default.px4board @@ -26,6 +26,7 @@ CONFIG_COMMON_MAGNETOMETER=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_COMMON_TELEMETRY=y CONFIG_DRIVERS_TONE_ALARM=y CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y diff --git a/boards/micoair/h743-aio/default.px4board b/boards/micoair/h743-aio/default.px4board index 67611b854c..7ddff044b7 100644 --- a/boards/micoair/h743-aio/default.px4board +++ b/boards/micoair/h743-aio/default.px4board @@ -36,6 +36,7 @@ CONFIG_DRIVERS_PPS_CAPTURE=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_COMMON_RC=y CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_COMMON_RPM=y CONFIG_DRIVERS_SMART_BATTERY_BATMON=y CONFIG_DRIVERS_TAP_ESC=y diff --git a/boards/nxp/mr-canhubk3/fmu.px4board b/boards/nxp/mr-canhubk3/fmu.px4board index ceab70761a..513290e7c3 100644 --- a/boards/nxp/mr-canhubk3/fmu.px4board +++ b/boards/nxp/mr-canhubk3/fmu.px4board @@ -22,6 +22,7 @@ CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IRLOCK=y CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_UAVCAN=y CONFIG_EXAMPLES_FAKE_GPS=y diff --git a/boards/px4/fmu-v2/rover.px4board b/boards/px4/fmu-v2/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/px4/fmu-v2/rover.px4board +++ b/boards/px4/fmu-v2/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/px4/fmu-v3/rover.px4board b/boards/px4/fmu-v3/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/px4/fmu-v3/rover.px4board +++ b/boards/px4/fmu-v3/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/px4/fmu-v4/rover.px4board b/boards/px4/fmu-v4/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/px4/fmu-v4/rover.px4board +++ b/boards/px4/fmu-v4/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/px4/fmu-v4pro/rover.px4board b/boards/px4/fmu-v4pro/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/px4/fmu-v4pro/rover.px4board +++ b/boards/px4/fmu-v4pro/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/px4/fmu-v5/rover.px4board b/boards/px4/fmu-v5/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/px4/fmu-v5/rover.px4board +++ b/boards/px4/fmu-v5/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/px4/fmu-v5x/rover.px4board b/boards/px4/fmu-v5x/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/px4/fmu-v5x/rover.px4board +++ b/boards/px4/fmu-v5x/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/px4/fmu-v6c/rover.px4board b/boards/px4/fmu-v6c/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/px4/fmu-v6c/rover.px4board +++ b/boards/px4/fmu-v6c/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/px4/fmu-v6u/rover.px4board b/boards/px4/fmu-v6u/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/px4/fmu-v6u/rover.px4board +++ b/boards/px4/fmu-v6u/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/px4/fmu-v6x/rover.px4board b/boards/px4/fmu-v6x/rover.px4board index cd49a241b5..d9bfec2d68 100644 --- a/boards/px4/fmu-v6x/rover.px4board +++ b/boards/px4/fmu-v6x/rover.px4board @@ -12,6 +12,7 @@ CONFIG_MODULES_MC_POS_CONTROL=n CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/px4/fmu-v6xrt/rover.px4board b/boards/px4/fmu-v6xrt/rover.px4board index 0a092749c5..5b934d8a80 100644 --- a/boards/px4/fmu-v6xrt/rover.px4board +++ b/boards/px4/fmu-v6xrt/rover.px4board @@ -13,6 +13,7 @@ CONFIG_MODULES_MC_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL=n CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_HIWONDER_EMM=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index 4f5f5f4a73..51973e08da 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -307,6 +307,7 @@ - [DroneCAN ESCs](dronecan/escs.md) - [PX4 Sapog ESC Firmware](dronecan/sapog.md) - [ARK 4IN1 ESC](esc/ark_4in1_esc.md) + - [Hiwonder 4Ch Encoder Motor Module](peripherals/hiwonder_emm.md) - [Holybro Kotleta](dronecan/holybro_kotleta.md) - [Vertiq Motor/ESC Modules](peripherals/vertiq.md) - [VESC Project ESCs](peripherals/vesc.md) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index bd8c9d57a8..b84611bd05 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -28,6 +28,11 @@ Enable ADS7953. Enable the driver for the ADS7953 board +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -191,6 +196,11 @@ ADSB-Out Ident Configuration. Enable Identification of Position feature +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -266,6 +276,434 @@ This parameter defines the squawk code. Value should be between 0000 and 7777. ## Actuator Outputs +### EMM_DIS1 (`INT32`) {#EMM_DIS1} + + + +Hiwonder EMM Driver Channel 1 Disarmed Value. + +This is the output value that is set when not armed. + +Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | 0 | 255 | | 128 | |   | + +### EMM_DIS2 (`INT32`) {#EMM_DIS2} + + + +Hiwonder EMM Driver Channel 2 Disarmed Value. + +This is the output value that is set when not armed. + +Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | 0 | 255 | | 128 | |   | + +### EMM_DIS3 (`INT32`) {#EMM_DIS3} + + + +Hiwonder EMM Driver Channel 3 Disarmed Value. + +This is the output value that is set when not armed. + +Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | 0 | 255 | | 128 | |   | + +### EMM_DIS4 (`INT32`) {#EMM_DIS4} + + + +Hiwonder EMM Driver Channel 4 Disarmed Value. + +This is the output value that is set when not armed. + +Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | 0 | 255 | | 128 | |   | + +### EMM_FAIL1 (`INT32`) {#EMM_FAIL1} + + + +Hiwonder EMM Driver Channel 1 Failsafe Value. + +This is the output value that is set when in failsafe mode. + +When set to -1 (default), the value depends on the function (see EMM_FUNC1). + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | -1 | 255 | | -1 | |   | + +### EMM_FAIL2 (`INT32`) {#EMM_FAIL2} + + + +Hiwonder EMM Driver Channel 2 Failsafe Value. + +This is the output value that is set when in failsafe mode. + +When set to -1 (default), the value depends on the function (see EMM_FUNC2). + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | -1 | 255 | | -1 | |   | + +### EMM_FAIL3 (`INT32`) {#EMM_FAIL3} + + + +Hiwonder EMM Driver Channel 3 Failsafe Value. + +This is the output value that is set when in failsafe mode. + +When set to -1 (default), the value depends on the function (see EMM_FUNC3). + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | -1 | 255 | | -1 | |   | + +### EMM_FAIL4 (`INT32`) {#EMM_FAIL4} + + + +Hiwonder EMM Driver Channel 4 Failsafe Value. + +This is the output value that is set when in failsafe mode. + +When set to -1 (default), the value depends on the function (see EMM_FUNC4). + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | -1 | 255 | | -1 | |   | + +### EMM_FUNC1 (`INT32`) {#EMM_FUNC1} + + + +Hiwonder EMM Driver Channel 1 Output Function. + +Select what should be output on Hiwonder EMM Driver Channel 1. + +The default failsafe value is set according to the selected function: + +- 'Min' for ConstantMin +- 'Max' for ConstantMax +- 'Max' for Parachute +- ('Max'+'Min')/2 for Servos +- 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | | | | 0 | |   | + +### EMM_FUNC2 (`INT32`) {#EMM_FUNC2} + + + +Hiwonder EMM Driver Channel 2 Output Function. + +Select what should be output on Hiwonder EMM Driver Channel 2. + +The default failsafe value is set according to the selected function: + +- 'Min' for ConstantMin +- 'Max' for ConstantMax +- 'Max' for Parachute +- ('Max'+'Min')/2 for Servos +- 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | | | | 0 | |   | + +### EMM_FUNC3 (`INT32`) {#EMM_FUNC3} + + + +Hiwonder EMM Driver Channel 3 Output Function. + +Select what should be output on Hiwonder EMM Driver Channel 3. + +The default failsafe value is set according to the selected function: + +- 'Min' for ConstantMin +- 'Max' for ConstantMax +- 'Max' for Parachute +- ('Max'+'Min')/2 for Servos +- 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | | | | 0 | |   | + +### EMM_FUNC4 (`INT32`) {#EMM_FUNC4} + + + +Hiwonder EMM Driver Channel 4 Output Function. + +Select what should be output on Hiwonder EMM Driver Channel 4. + +The default failsafe value is set according to the selected function: + +- 'Min' for ConstantMin +- 'Max' for ConstantMax +- 'Max' for Parachute +- ('Max'+'Min')/2 for Servos +- 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | | | | 0 | |   | + +### EMM_REV (`INT32`) {#EMM_REV} + + + +Reverse Output Range for Hiwonder EMM Driver. + +Allows to reverse the output range for each channel. +Note: this is only useful for servos. + +**Bitmask:** + +- `0`: Hiwonder EMM Driver Channel 1 +- `1`: Hiwonder EMM Driver Channel 2 +- `2`: Hiwonder EMM Driver Channel 3 +- `3`: Hiwonder EMM Driver Channel 4 + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------ | -------- | -------- | --------- | ------- | ---- | --------- | +|   | 0 | 15 | | 0 | |   | + ### PCA9685_CENT1 (`INT32`) {#PCA9685_CENT1} @@ -17381,6 +17819,11 @@ When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this Acceleration compensation based on GPS velocity. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -17399,6 +17842,11 @@ standalone attitude estimator enable (unsupported). Enable standalone quaternion based attitude estimator. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -17436,6 +17884,11 @@ GPS coordinates of the vehicle. Automatic GPS based declination compensation. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -17607,6 +18060,11 @@ the drone properly. Multicopter autotune module enable. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -18232,6 +18690,11 @@ Camera capture feedback. Enables camera capture feedback +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -18511,6 +18974,11 @@ Require arm authorization to arm. By default off. The default allows to arm the vehicle without a arm authorization. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -18545,6 +19013,11 @@ Enable checks on ESCs that report telemetry. If this parameter is set, the system will check ESC's online status and failures. This param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -18556,6 +19029,11 @@ Enable FMU SD card hardfault / watchdog detection check. This check detects if there are hardfault / watchdog files present on the SD card. If so, and the parameter is enabled, arming is prevented. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -18615,6 +19093,11 @@ Require valid mission to arm. The default allows to arm the vehicle without a valid mission. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -18646,6 +19129,11 @@ When enabled, the vehicle arms automatically once all preflight checks pass afte The vehicle will not re-arm after a manual disarm. Has no effect if COM_ARMABLE is 0. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -18657,6 +19145,11 @@ Arm switch is a momentary button. 0: Arming/disarming triggers on switch transition. 1: Arming/disarming triggers when holding the momentary button down like the stick gesture. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -19062,6 +19555,11 @@ Enable force safety. Force safety when the vehicle disarms +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -19107,6 +19605,11 @@ During missions, the latitude/longitude of the home position is locked and will It will only update once the mission is complete or landed outside of a mission. However, the altitude is still being adjusted to correct for GNSS vertical drift in the first 2 minutes after takeoff. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -19119,6 +19622,11 @@ If set to true, the autopilot is allowed to set its home position after takeoff The true home position is back-computed if a local position is estimate if available. If no local position is available, home is set to the current position. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -19242,6 +19750,11 @@ Allow external mode registration while armed. By default disabled for safety reasons +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -19284,6 +19797,11 @@ See COM_OBL_RC_ACT to configure action. Require MAVLink parachute system to be present and healthy. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -19512,6 +20030,11 @@ Enable throw-start. Allows to start the vehicle by throwing it into the air. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -19647,6 +20170,11 @@ Cyphal. 0 - Cyphal disabled. 1 - Enables Cyphal +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -19871,6 +20399,11 @@ Direction 1) 48 is the slowest, 1047 is the fastest. Direction 2) 1049 is the slowest, 2047 is the fastest. When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -19883,6 +20416,11 @@ This parameter enables Extended DShot Telemetry which allows transmission of additional telemetry within the eRPM frame. The EDT data is interleaved with the eRPM frames at a low rate. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -20493,6 +21031,11 @@ Barometric sensor height aiding. If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -20592,6 +21135,11 @@ Multirotor wind estimation selection. Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2*BCOEF*[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -20618,6 +21166,11 @@ Measurement noise for airspeed fusion. EKF2 enable. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -20758,6 +21311,11 @@ Enable synthetic sideslip fusion. For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. Only applies to vehicles in fixed-wing mode or with airspeed fusion active. Note: side slip fusion is currently not supported for tailsitters. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -21019,6 +21577,11 @@ Forward axis with origin relative to vehicle centre of gravity Verbose logging. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -21200,6 +21763,11 @@ Optical flow aiding. Enable optical flow fusion. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -21365,6 +21933,11 @@ Enable constant position fusion while on ground. When enabled, constant position fusion is enabled when the vehicle is landeded if position has been initialized but has currently no vel/pos aiding. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -21730,6 +22303,11 @@ Enable synthetic magnetometer Z component measurement. Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -21834,6 +22412,11 @@ if the vehicle was previously armed and only if the vehicle had RC signal at some point. Particularly useful for locating crashed drones without a GPS sensor. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -21847,6 +22430,11 @@ LEDs. When enabled and if the vehicle supports it, LEDs will flash indicating various vehicle status changes. Currently PX4 has not implemented any specific status events. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -21987,6 +22575,11 @@ Enable wheel steering controller. Only enabled during automatic runway takeoff and landing. In all manual modes the wheel is directly controlled with yaw stick. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -22077,6 +22670,11 @@ Allows to deploy the landing configuration (flaps, landing airspeed, etc.) alrea the loiter-down waypoint before the final approach. Otherwise is enabled only in the final approach. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -22270,6 +22868,11 @@ Fixed-wing launch detection. Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. Not compatible with runway takeoff. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -22669,6 +23272,11 @@ Enable automatic lower bound on the NPFG period. Avoids limit cycling from a too aggressively tuned period/damping combination. If false, also disables upper bound NPFG_PERIOD_UB. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -22722,6 +23330,11 @@ Enable automatic upper bound on the NPFG period. Adapts period to maintain track keeping in variable winds and path curvature. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -22901,6 +23514,11 @@ Otherwise the pilot commands directly the yaw actuator. It is disabled by default because an active yaw rate controller will fight against the natural turn coordination of the plane. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -22932,6 +23550,11 @@ the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro) +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -22943,6 +23566,11 @@ Enable throttle scale by battery level. This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -23031,6 +23659,11 @@ Chose source for manual setting of flaps in manual flight modes. Enable rate gain compression. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -23207,6 +23840,11 @@ If set to 1, the airspeed measurement data, if valid, is used in the following c - Position controller: airspeed setpoint tracking, takeoff logic - VTOL: transition logic +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -23284,6 +23922,11 @@ Enable PWM input on for engaging failsafe from an external automatic trigger sys Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -23641,6 +24284,11 @@ To avoid these kind of problems a clean config can be reached by wiping the FLAS Note: Currently only supported on UBX. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -23672,6 +24320,11 @@ Enable sat info (if available). Enable publication of satellite info (ORB_ID(satellite_info)) if possible. Not available on MTK. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -23743,6 +24396,11 @@ Enables or disables the high sensitivity mode for the u-blox jamming detection more sensitive algorithm to detect jamming. Disabling this may reduce false positives in electrically noisy environments. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -23803,6 +24461,11 @@ Mode 6 is intended for use with a ground control station (not necessarily an RTK Enable MSM7 message output for PPK workflow. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -23851,6 +24514,11 @@ PPS capture enable. Enables the PPS capture module to refine the GPS time from pulses detected on a PWM pin configured as "PPS Input". +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -23924,6 +24592,11 @@ Predict the motion of the vehicle and trigger the breach if it is determined tha would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -24167,6 +24840,11 @@ positive thrust of the tail rotor is expected to rotate the vehicle clockwise. Set this parameter to true if the tail rotor provides thrust in counter-clockwise direction which is mostly the case when the main rotor turns counter-clockwise. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -26929,6 +27607,21 @@ Currently only supported in gz simulation and must be coherent with .sdf file an | ------ | -------- | -------- | --------- | ------- | ---- | --------- | |   | -180.0 | 180.0 | | -45.0 | deg |   | +## Hiwonder EMM + +### HIWONDER_EMM_EN (`INT32`) {#HIWONDER_EMM_EN} + +Enable the Hiwonder Encoder Motor Module (EMM) motor driver. + +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------- | -------- | -------- | --------- | ------------ | ---- | --------- | +| ✓ | | | | Disabled (0) | |   | + ## Hover Thrust Estimator ### HTE_ACC_GATE (`FLOAT`) {#HTE_ACC_GATE} @@ -27019,6 +27712,11 @@ Duration of choking during startup. Enable internal combustion engine. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -27063,6 +27761,11 @@ Fault detection if it stops in running state. Enables restart if a fault is detected during the running state. Otherwise commands continues in running state until given an user request off. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -27071,6 +27774,11 @@ commands continues in running state until given an user request off. Apply choke when stopping engine. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -27466,6 +28174,11 @@ Barometric pressure altitude z standard deviation. Local position estimator enable (unsupported). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -27875,6 +28588,11 @@ message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -27926,6 +28644,11 @@ If enabled, MAVLink messages will be throttled according to Requires a radio to send the mavlink message RADIO_STATUS. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -28038,6 +28761,11 @@ message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -28089,6 +28817,11 @@ If enabled, MAVLink messages will be throttled according to Requires a radio to send the mavlink message RADIO_STATUS. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -28201,6 +28934,11 @@ message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -28252,6 +28990,11 @@ If enabled, MAVLink messages will be throttled according to Requires a radio to send the mavlink message RADIO_STATUS. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -28309,6 +29052,11 @@ Forward external setpoint messages. If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -28320,6 +29068,11 @@ Parameter hash check. Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -28331,6 +29084,11 @@ Heartbeat message forwarding. The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -28387,6 +29145,11 @@ Enable MAVLink forwarding on TELEM2. TELEM2 on Skynode only. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -28446,6 +29209,11 @@ Use/Accept HIL GPS message even if not in HIL mode. If set to 1 incoming HIL GPS messages are parsed. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -28510,6 +29278,11 @@ Enable online mag bias calibration. This enables continuous calibration of the magnetometers before takeoff using gyro data. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -28534,6 +29307,11 @@ Enable arm/disarm stick gesture. This determines if moving the left stick to the lower right arms and to the lower left disarms the vehicle. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -28712,6 +29490,11 @@ For fixed wing the npfg switch distance is used for horizontal acceptance. Force VTOL mode takeoff and land. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -28759,6 +29542,11 @@ the vehicle will loiter at the position where the last GCS heartbeat was received rather than at its current position. Only applies to Hold mode during failsafe actions. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -28897,6 +29685,11 @@ level is being consumed. Otherwise this indicates an motor failure. This check only works for ESCs that report current consumption. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -29396,6 +30189,11 @@ Boolean to allow moving into directions where there is no sensor data (outside F Only used in Position mode. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -29430,6 +30228,11 @@ Set to decouple tilt from vertical acceleration. This provides smoother flight but slightly worse tracking in position and auto modes. Unset if accurate position tracking during dynamic maneuvers is more important than a smooth flight. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -30100,6 +30903,11 @@ If set to a negative value, the existing individual parameters are used. Enable weathervane. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -30272,6 +31080,11 @@ Enable Raptor flight mode. When enabled, the Raptor flight mode will be available. Please set MC_RAPTOR_OFFB according to your use case. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -30299,6 +31112,11 @@ Enable Offboard mode replacement. When enabled, the Raptor mode will replace the Offboard mode. If disabled, the Raptor mode will be available as a separate external mode. In the latter case, Raptor will just hold the position, without requiring external setpoints. When Raptor replaces the Offboard mode, it requires external setpoints to be activated. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -30309,6 +31127,11 @@ Enable verbose output. When enabled, the Raptor flight mode will print verbose output to the console. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -30325,6 +31148,11 @@ should constantly behave as if it was fully charged with reduced max acceleratio at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -30559,6 +31387,11 @@ Can be set to increase the amount of integrator available to counteract disturba If true the neural network control is automatically started on boot. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -30567,6 +31400,11 @@ If true the neural network control is automatically started on boot. Enable or disable setting the trajectory setpoint with manual control. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -30741,6 +31579,11 @@ S.BUS out. Set to 1 to enable S.BUS version 1 output instead of RSSI. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -30891,6 +31734,11 @@ Crossfire RC telemetry enable. Crossfire telemetry enable +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -30901,6 +31749,11 @@ Ghost RC telemetry enable. Ghost telemetry enable +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -32942,6 +33795,11 @@ RTL force approach landing. Only consider RTL point, if it has an approach defined. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -33406,6 +34264,11 @@ Enable use of yaw stick for nudging the wheel during runway ground roll This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course. Particularly useful for skinny runways or if the wheel servo is a bit off trim. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -33459,6 +34322,11 @@ This is the time desired to linearly ramp in takeoff pitch constraints during th Runway takeoff with landing gear. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -33501,6 +34369,11 @@ Battery-only Logging. When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -33630,6 +34503,11 @@ Log UUID. If set to 1, add an ID to the log, which uniquely identifies the vehicle +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -35718,6 +36596,11 @@ Reverse differential pressure sensor readings. Reverse the raw measurements of all differential pressure sensors. This can be enabled if the sensors have static and dynamic ports swapped. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -35768,6 +36651,11 @@ Enable external ADS1115 ADC. If enabled, the internal ADC is not used. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -36127,6 +37015,11 @@ A value of 0 disables the filter. IMU gyro auto calibration enable. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -36195,6 +37088,11 @@ Minimum notch filter frequency in Hz. IMU gyro FFT enable. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -36909,6 +37807,11 @@ sbgECom driver INS configuration enable. Enable SBG Systems INS configuration through sbgECom driver on start. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -37044,6 +37947,11 @@ Barometer auto calibration. Automatically calibrate barometer based on the GNSS height +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -37198,6 +38106,11 @@ Analog Devices ADIS16448 IMU (external SPI). Analog Devices ADIS16507 IMU (external SPI). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37232,6 +38145,11 @@ Enable simulated airspeed sensor instance. ASP5033 differential pressure sensor (external I2C). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37269,6 +38187,11 @@ Enable simulated barometer sensor instance. SMBUS Smart battery driver BQ40Z50 and BQ40Z80. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37277,6 +38200,11 @@ SMBUS Smart battery driver BQ40Z50 and BQ40Z80. Eagle Tree airspeed sensor (external I2C). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37325,6 +38253,11 @@ Enable INA220 Power Monitor. For systems with an INA220 Power Monitor, this should be set to true +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37335,6 +38268,11 @@ Enable INA226 Power Monitor. For systems with an INA226 Power Monitor, this should be set to true +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37345,6 +38283,11 @@ Enable INA228 Power Monitor. For systems with an INA228 Power Monitor, this should be set to true +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37355,6 +38298,11 @@ Enable INA238 Power Monitor. For systems with an INA238 Power Monitor, this should be set to true +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37363,6 +38311,11 @@ For systems with an INA238 Power Monitor, this should be set to true IR-LOCK Sensor (external I2C). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37398,6 +38351,11 @@ Enable simulated magnetometer sensor instance. Maxbotix Sonar (mb12xx). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37406,6 +38364,11 @@ Maxbotix Sonar (mb12xx). Enable MCP9808 temperature sensor (external I2C). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37427,6 +38390,11 @@ Enable Mappydot rangefinder (i2c). TE MS4515 differential pressure sensor (external I2C). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37435,6 +38403,11 @@ TE MS4515 differential pressure sensor (external I2C). TE MS4525DO differential pressure sensor (external I2C). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37443,6 +38416,11 @@ TE MS4525DO differential pressure sensor (external I2C). TE MS5525DSO differential pressure sensor (external I2C). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37451,6 +38429,11 @@ TE MS5525DSO differential pressure sensor (external I2C). PAA3905 Optical Flow. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37459,6 +38442,11 @@ PAA3905 Optical Flow. PAW3902/PAW3903 Optical Flow. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37482,6 +38470,11 @@ Run PCF8583 driver automatically PGA460 Ultrasonic driver (PGA460). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37490,6 +38483,11 @@ PGA460 Ultrasonic driver (PGA460). PMW3901 Optical Flow. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37498,6 +38496,11 @@ PMW3901 Optical Flow. PX4 Flow Optical Flow. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37519,6 +38522,11 @@ Murata SCH16T IMU (external SPI). Sensirion SDP3X differential pressure sensor (external I2C). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37592,6 +38600,11 @@ Configure on which serial port to run Lightware SF45 Rangefinder (serial). SHT3x temperature and hygrometer. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37600,6 +38613,11 @@ SHT3x temperature and hygrometer. Goertek SPA06 Barometer (external I2C). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37608,6 +38626,11 @@ Goertek SPA06 Barometer (external I2C). Goertek SPL06 Barometer (external I2C). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37616,6 +38639,11 @@ Goertek SPL06 Barometer (external I2C). HY-SRF05 / HC-SR05. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37624,6 +38652,11 @@ HY-SRF05 / HC-SR05. TF02 Pro Distance Sensor (i2c). +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37648,6 +38681,11 @@ Enable TMP102. Enable the driver for the TMP102 temperature sensor +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37673,6 +38711,11 @@ TeraRanger Rangefinder (i2c). VL53L0X Distance Sensor. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37681,6 +38724,11 @@ VL53L0X Distance Sensor. VL53L1X Distance Sensor. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -37691,6 +38739,11 @@ External I2C probe. Probe for optional external I2C devices. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -37955,6 +39008,11 @@ IMU auto calibration. Automatically initialize IMU (accel/gyro) calibration from bias estimates if available. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -37965,6 +39023,11 @@ IMU notify clipping. Notify the user if the IMU is clipping +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -37988,6 +39051,11 @@ Enable internal barometers. For systems with an external barometer, this should be set to false to make sure that the external is used. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -38023,6 +39091,11 @@ Magnetometer auto calibration. Automatically initialize magnetometer calibration from bias estimate if available. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -38033,6 +39106,11 @@ Automatically set external rotations. During calibration attempt to automatically determine the rotation of external magnetometers. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -38913,6 +39991,11 @@ By default, the receiver is automatically configured. Sometimes it may be used f If the offered parameters aren't sufficient, this parameter can be disabled to have full control of the receiver configuration. A good way to use this is to enable automatic configuration, let the receiver be configured, and then disable it to make manual adjustments. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -38977,6 +40060,11 @@ Whether to overwrite or add to existing logging. When the receiver is already set up to log data, this decides whether extra logged data should be added or overwrite existing data. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -39110,6 +40198,11 @@ Enable sat info. Enable publication of satellite info (ORB_ID(satellite_info)) if possible. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -40303,6 +41396,11 @@ RPM capture enable. Enables the RPM capture module to estimate RPM from pulses detected on a PWM pin configured as "RPM Input". +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -40361,6 +41459,11 @@ Instructions: - Wait until the board comes back up (or at least 2 minutes) - If it does not come back, check the file bootlog.txt on the SD card +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -40490,6 +41593,11 @@ If enabled allows MAVLink INJECT_FAILURE commands. WARNING: the failures can easily cause crashes and are to be used with caution! +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -40503,6 +41611,11 @@ F4 SD variants. If disabled, the preflight checks will not check for the presence of a barometer. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -40515,6 +41628,11 @@ Disable this if the system has no GPS. If disabled, the sensors hub will not process sensor_gps, and GPS will not be available for the rest of the system. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -40587,6 +41705,11 @@ When this is enabled all the hardfaults on the SD card are streamed over MAVLink. This is useful for cases where the FMU does reset in-flight due to a hardfault and the SD card may not survive a crash. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -40641,6 +41764,11 @@ Set to 0 to disable, 1 for maximum brightness Enable stack checking. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -40653,6 +41781,11 @@ Blacksheep telemetry Enable. If true, the FMU will try to connect to Blacksheep telemetry on start up +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -41323,6 +42456,11 @@ Accelerometer offset temperature ^3 polynomial coefficient - Z axis. Thermal compensation for accelerometer sensors. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -41651,6 +42789,11 @@ Barometer offset temperature ^5 polynomial coefficient. Thermal compensation for barometric pressure sensors. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -42171,6 +43314,11 @@ Gyro rate offset temperature ^3 polynomial coefficient - Z axis. Thermal compensation for rate gyro sensors. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -42691,6 +43839,11 @@ Magnetometer offset temperature ^3 polynomial coefficient - Z axis. Thermal compensation for magnetometer sensors. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -42703,6 +43856,11 @@ Sagetech External Configuration Mode. Disables auto-configuration mode enabling MXS config through external software. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -42790,6 +43948,11 @@ Enable barometer publication. Enables publication of static pressure and static temperature from the barometer sensor over UAVCAN. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | 1 | | Enabled (1) | |   | @@ -42798,6 +43961,11 @@ from the barometer sensor over UAVCAN. Enable RawIMU pub. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | 1 | | Disabled (0) | |   | @@ -42809,6 +43977,11 @@ Enable magnetometer publication. Enables publication of magnetic field strength from the magnetometer sensor over UAVCAN. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | 1 | | Enabled (1) | |   | @@ -42817,6 +43990,11 @@ from the magnetometer sensor over UAVCAN. Enable MovingBaselineData publication. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -42825,6 +44003,11 @@ Enable MovingBaselineData publication. Enable MovingBaselineData subscription. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | 1 | | Disabled (0) | |   | @@ -42833,6 +44016,11 @@ Enable MovingBaselineData subscription. Enable RTCM subscription. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -42841,6 +44029,11 @@ Enable RTCM subscription. CAN built-in bus termination. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | 1 | | Disabled (0) | |   | @@ -42849,6 +44042,11 @@ CAN built-in bus termination. Simulator Gazebo bridge enable. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43057,6 +44255,11 @@ publish Arming Status stream. Enable UAVCAN Arming Status stream publication uavcan::equipment::safety::ArmingStatus +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43068,6 +44271,11 @@ publish moving baseline data RTCM stream. Enable UAVCAN RTCM stream publication ardupilot::gnss::MovingBaselineData +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43079,6 +44287,11 @@ publish RTCM stream. Enable UAVCAN RTCM stream publication uavcan::equipment::gnss::RTCMStream +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43112,6 +44325,11 @@ uavcan::equipment::air_data::IndicatedAirspeed uavcan::equipment::air_data::TrueAirspeed uavcan::equipment::air_data::StaticTemperature +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43124,6 +44342,11 @@ Enable UAVCAN barometer subscription. uavcan::equipment::air_data::StaticPressure uavcan::equipment::air_data::StaticTemperature +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43158,6 +44381,11 @@ subscription button. Enable UAVCAN button subscription. ardupilot::indication::Button +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43169,6 +44397,11 @@ subscription differential pressure. Enable UAVCAN differential pressure subscription. uavcan::equipment::air_data::RawAirData +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43179,6 +44412,11 @@ subscription flow. Enable UAVCAN optical flow subscription. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43189,6 +44427,11 @@ subscription fuel tank. Enable UAVCAN fuel tank status subscription. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43202,6 +44445,11 @@ uavcan::equipment::gnss::Fix uavcan::equipment::gnss::Fix2 uavcan::equipment::gnss::Auxiliary +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -43213,6 +44461,11 @@ subscription GPS Relative. Enable UAVCAN GPS Relative subscription. ardupilot::gnss::RelPosHeading +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -43224,6 +44477,11 @@ subscription hygrometer. Enable UAVCAN hygrometer subscriptions. dronecan::sensors::hygrometer::Hygrometer +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43235,6 +44493,11 @@ subscription ICE. Enable UAVCAN internal combustion engine (ICE) subscription. uavcan::equipment::ice::reciprocating::Status +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43246,6 +44509,11 @@ subscription IMU. Enable UAVCAN IMU subscription. uavcan::equipment::ahrs::RawIMU +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43258,6 +44526,11 @@ Enable UAVCAN mag subscription. uavcan::equipment::ahrs::MagneticFieldStrength uavcan::equipment::ahrs::MagneticFieldStrength2 +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -43269,6 +44542,11 @@ subscription MovingBaselineData. Enable UAVCAN MovingBaselineData subscription. ardupilot::gnss::MovingBaselineData +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43280,10 +44558,30 @@ subscription range finder. Enable UAVCAN range finder subscription. uavcan::equipment::range_sensor::Measurement +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | +### UAVCAN_TRACE_EN (`INT32`) {#UAVCAN_TRACE_EN} + +UAVCAN event tracing. + +Enable logging of UAVCAN events + +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | Read-Only | +| ------- | -------- | -------- | --------- | ----------- | ---- | --------- | +| ✓ | | | | Enabled (1) | |   | + ## UUV Attitude Control ### UUV_HGT_B_DOWN (`INT32`) {#UUV_HGT_B_DOWN} @@ -43792,6 +45090,11 @@ Enable serial flow control for UXRCE interface. This is used to enable flow control for the serial uXRCE instance. Used for reliable high bandwidth communication. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43867,6 +45170,11 @@ Enable uXRCE-DDS system clock synchronization. When enabled along with UXRCE_DDS_SYNCT, uxrce_dds_client will set the system clock using the agents UTC timestamp. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | @@ -43877,6 +45185,11 @@ Enable uXRCE-DDS timestamp synchronization. When enabled, uxrce_dds_client will synchronize the timestamps of the incoming and outgoing messages measuring the offset between the Agent OS time and the PX4 time. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ----------- | ---- | --------- | | ✓ | | | | Enabled (1) | |   | @@ -44300,6 +45613,11 @@ Lock control surfaces in hover. If set to 1 the control surfaces are locked at the disarmed value in multicopter mode. +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ----------- | ---- | --------- | |   | | | | Enabled (1) | |   | @@ -44753,6 +46071,11 @@ VTX pit mode. VTX pit mode reduces power to the minimum +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -45008,6 +46331,11 @@ Reinitialize the target module's values into the PX4 parameters. Setting this value to true will reinitialize PX4's IQUART connected parameters to the value stored on the currently targeted motor. This is especially useful if your flight controller powered on before your connected modules +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------ | -------- | -------- | --------- | ------------ | ---- | --------- | |   | | | | Disabled (0) | |   | @@ -45183,6 +46511,11 @@ Set true (1) to start the Zenoh driver module (a.k.a the "Zenoh-Pico Node"). See https://docs.px4.io/main/en/middleware/zenoh and https://docs.px4.io/main/en/modules/modules_driver.html#zenoh +**Values:** + +- `0`: Disabled +- `1`: Enabled + | Reboot | minValue | maxValue | increment | default | unit | Read-Only | | ------- | -------- | -------- | --------- | ------------ | ---- | --------- | | ✓ | | | | Disabled (0) | |   | diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index c1292c9819..51092097ee 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -95,209 +95,209 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [RegisterExtComponentRequestV1](../msg_docs/RegisterExtComponentRequestV1.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [LedControl](../msg_docs/LedControl.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [RangingBeacon](../msg_docs/RangingBeacon.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [Mission](../msg_docs/Mission.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [Event](../msg_docs/Event.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [EscReport](../msg_docs/EscReport.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [EventV0](../msg_docs/EventV0.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [Vtx](../msg_docs/Vtx.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [Gripper](../msg_docs/Gripper.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [QshellRetval](../msg_docs/QshellRetval.md) - [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [VehicleStatusV3](../msg_docs/VehicleStatusV3.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [EscEepromRead](../msg_docs/EscEepromRead.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [InputRc](../msg_docs/InputRc.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [VehicleStatusV2](../msg_docs/VehicleStatusV2.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [EscEepromWrite](../msg_docs/EscEepromWrite.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) - [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [InputRc](../msg_docs/InputRc.md) - [SensorMag](../msg_docs/SensorMag.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [Rpm](../msg_docs/Rpm.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) - [SensorGyro](../msg_docs/SensorGyro.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [Ping](../msg_docs/Ping.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [VehicleStatusV2](../msg_docs/VehicleStatusV2.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [Vtx](../msg_docs/Vtx.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [OrbTest](../msg_docs/OrbTest.md) - [DebugValue](../msg_docs/DebugValue.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [Gripper](../msg_docs/Gripper.md) +- [Rpm](../msg_docs/Rpm.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) - [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) - [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [Ping](../msg_docs/Ping.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [EstimatorFusionControl](../msg_docs/EstimatorFusionControl.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [GpsDump](../msg_docs/GpsDump.md) - [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [EventV0](../msg_docs/EventV0.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [Event](../msg_docs/Event.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [EscEepromRead](../msg_docs/EscEepromRead.md) - [PwmInput](../msg_docs/PwmInput.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [RegisterExtComponentRequestV1](../msg_docs/RegisterExtComponentRequestV1.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [EscEepromWrite](../msg_docs/EscEepromWrite.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [Mission](../msg_docs/Mission.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [EscReport](../msg_docs/EscReport.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [RangingBeacon](../msg_docs/RangingBeacon.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [VehicleStatusV3](../msg_docs/VehicleStatusV3.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [LedControl](../msg_docs/LedControl.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [EstimatorFusionControl](../msg_docs/EstimatorFusionControl.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [QshellRetval](../msg_docs/QshellRetval.md) ::: diff --git a/docs/en/modules/modules_driver.md b/docs/en/modules/modules_driver.md index 3a42139fe2..635b19991c 100644 --- a/docs/en/modules/modules_driver.md +++ b/docs/en/modules/modules_driver.md @@ -432,6 +432,26 @@ gz_bridge [arguments...] status print status info ``` +## hiwonder_emm + +Source: [drivers/hiwonder_emm](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/hiwonder_emm) + +### Description + +Hiwonder encoder motor module driver for PX4. + +### Usage {#hiwonder_emm_usage} + +``` +hiwonder_emm [arguments...] + Commands: + start Start the task + + stop + + status print status info +``` + ## ina220 Source: [drivers/power_monitor/ina220](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/ina220) diff --git a/docs/en/peripherals/esc_motors.md b/docs/en/peripherals/esc_motors.md index 8849c357de..e5d4599506 100644 --- a/docs/en/peripherals/esc_motors.md +++ b/docs/en/peripherals/esc_motors.md @@ -12,6 +12,7 @@ The following list is non-exhaustive. | ESC Device | Protocols | Firmwares | Notes | | ------------------------------ | ------------------------------------ | ------------------------ | ----------------------------------------------------- | | [ARK 4IN1 ESC] | [Dshot], [PWM] | [AM32] | Has versions with/without connectors | +| [Hiwonder 4Ch Encoder Motor] | I2C | | Brushed-DC, 4 channels with encoder feedback (rovers) | | [Holybro Kotleta 20] | [DroneCAN], [PWM] | [PX4 Sapog ESC Firmware] | | | [Vertiq Motor & ESC modules] | [Dshot], [OneShot], Multishot, [PWM] | Vertiq firmware | Larger modules support DroneCAN, ESC and Motor in one | | [RaccoonLab CAN PWM ESC nodes] | [DroneCAN], Cyphal | | Cyphal and DroneCAN notes for PWM ESC | @@ -21,6 +22,7 @@ The following list is non-exhaustive. [ARK 4IN1 ESC]: ../esc/ark_4in1_esc.md +[Hiwonder 4Ch Encoder Motor]: ../peripherals/hiwonder_emm.md [AM32]: https://am32.ca/ [PX4 Sapog ESC Firmware]: ../dronecan/sapog.md [VESC ESCs]: ../peripherals/vesc.md diff --git a/docs/en/peripherals/hiwonder_emm.md b/docs/en/peripherals/hiwonder_emm.md new file mode 100644 index 0000000000..74b1f8e337 --- /dev/null +++ b/docs/en/peripherals/hiwonder_emm.md @@ -0,0 +1,53 @@ +# Hiwonder 4-Channel Encoder Motor Module + +The [Hiwonder 4-Channel Encoder Motor Driver](https://www.hiwonder.com/products/4-channel-encoder-motor-driver) is a small I2C motor controller with integrated encoder feedback for up to four brushed DC motors. +It is well suited to small wheeled rovers (differential, ackermann, or mecanum) where size, weight, and a low channel count make a full-size ESC overkill. + +PX4 supports the board via the `hiwonder_emm` I2C driver. + +## Features + +- Four independent motor outputs with closed-loop speed control from on-board encoders. +- I2C interface (default address `0x34`, 400 kHz). +- Battery voltage telemetry of the supply rail powering the motor outputs. +- Selectable motor types (TT, N20, JGB37-520-12V-110RPM, or open-loop "no encoder"). + +## Where to Buy + +- [Hiwonder — 4-Channel Encoder Motor Driver product page](https://www.hiwonder.com/products/4-channel-encoder-motor-driver) + +## Hardware Setup + +### Wiring + +Connect the four motors (with their encoder leads) to channels `M1`–`M4` on the EMM and supply the motor driver from a battery suitable for the motors used. +Wire the EMM's I2C bus (`SDA`, `SCL`, `GND`) to an external I2C port on the flight controller. +The driver is hard-coded to bus `1` (the first external I2C bus) at address `0x34`, which is the board default. + +::: info +The driver auto-detects the four channels but the motor type is selected in firmware. +The shipped default is `JGB37-520-12V-110RPM`; change [`HiwonderEMM.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/drivers/hiwonder_emm/HiwonderEMM.cpp) (`set_motor_type`) if you use a different model. +::: + +## Flight Controller Setup + +### Enable the Driver + +Set the [HIWONDER_EMM_EN](../advanced_config/parameter_reference.md#HIWONDER_EMM_EN) parameter to `1` and reboot. + +The driver is started automatically by the rover startup script ([`rc.rover`](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d/rc.rover)), which runs for every ackermann, differential, and mecanum airframe. +It is compiled into builds that enable `CONFIG_DRIVERS_HIWONDER_EMM` in the board configuration. + +### Actuator Allocation + +The driver exposes a four-channel output group with the `EMM` parameter prefix. +In [Actuator Configuration](../config/actuators.md), assign the rover wheel outputs (e.g. `Motor 1`, `Motor 2`, …) to channels `EMM 1`–`EMM 4` matching how the motors are wired to the EMM. + +The output range is fixed in firmware to `0..255` (the EMM's protocol range, internally mapped to a signed `[-128, 127]` speed command — `128` is stop, values below are reverse, values above are forward). +`EMM_DIS{i}` (disarmed) and `EMM_FAIL{i}` (failsafe) per-channel parameters are user-tunable in the standard range. + +## Further Information + +- Driver source: [`src/drivers/hiwonder_emm`](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/hiwonder_emm) +- [Actuator Configuration](../config/actuators.md) +- [Rovers](../frames_rover/index.md) diff --git a/docs/en/releases/1.17.md b/docs/en/releases/1.17.md index 85643647da..b7a8c847e8 100644 --- a/docs/en/releases/1.17.md +++ b/docs/en/releases/1.17.md @@ -13,122 +13,350 @@ const { site } = useData(); -This contains changes in PX4 v1.17 (since the last major release [PX v1.16](../releases/1.16.md)). +PX4 v1.17 builds on [PX4 v1.16](../releases/1.16.md), with the changes below landing since v1.16.2. +This release adds [Altitude Cruise](../flight_modes_mc/altitude_cruise.md) mode, improves Fixed Wing Takeoff behaviour on navigation loss, and exposes cleaner high-level fixed-wing and rover control interfaces for ROS 2 workflows. +The in-tree Zenoh middleware matures to `rmw_zenoh` compatibility, simulation gains Gazebo Jetty support and Ackermann SIH, and three new INS drivers (MicroStrain, sbgECom, EULER-NAV) join the ecosystem alongside Septentrio GNSS resilience reporting and barometer auto-calibration against GNSS height. +PX4 v1.17 also includes user-visible MAVLink, RC, logging, failsafe, and rover refinements across the stack. ::: warning -PX4 v1.17 is in alpha/beta testing. -Update these notes with features that are going to be in PX4 v1.17 release. -New features that are not expected to go into the v1.17 release are in [PX4-Autopilot `main` Release Notes](../releases/main.md). +PX4 v1.17 is documented on an alpha/beta release branch. +See [PX4-Autopilot `main` Release Notes](../releases/main.md) for newer changes on `main`. ::: ## Read Before Upgrading -TBD … - Please continue reading for [upgrade instructions](#upgrade-guide). ## Major Changes -- TBD +- New multicopter flight mode: [Altitude Cruise](../flight_modes_mc/altitude_cruise.md). + Holds tilt and heading on stick release so the vehicle keeps cruising at a steady velocity instead of stopping like Altitude mode does. +- [Fixed Wing Takeoff mode](../flight_modes_fw/takeoff.md) now keeps climbing with level wings on navigation loss and can use the takeoff waypoint latitude and longitude to define the loiter position. + ([PX4-Autopilot#25226](https://github.com/PX4/PX4-Autopilot/pull/25226)) +- Fixed-wing vehicles (and VTOLs in fixed-wing mode) can now be controlled from ROS 2 via the new [`FwLateralLongitudinalSetpointType`](../ros2/px4_ros2_control_interface.md#fw-lateral-longitudinal-setpoint) in the PX4 ROS 2 Control Interface, exposing direct lateral and longitudinal setpoints. +- Rovers can now be controlled from ROS 2 via the new [`RoverSetpointTypes`](../ros2/px4_ros2_control_interface.md#rover-setpoints) in the PX4 ROS 2 Control Interface, with valid combinations of position, speed, throttle, attitude, rate, and steering setpoints exposed as guaranteed-valid setpoint types. See [Rovers Apps & API](../flight_modes_rover/api.md). +- The in-tree [Zenoh middleware](../middleware/zenoh.md) matures to `rmw_zenoh` compatibility (CDRv1 serialization, ROS 2 graph liveliness, auto-generated config from `dds_topics.yaml`, Domain ID parameter, Zenoh CLI). Zenoh is built into the default firmware on FMU-v6xRT (`make px4_fmu-v6xrt_default`); on FMU-v6x and SITL it ships as a `zenoh` build variant (`make px4_fmu-v6x_zenoh`, `make px4_sitl_zenoh`). +- Initial [MC Neural Network Control](../neural_networks/mc_neural_network_control.md) test path: PX4 v1.17 integrates [TensorFlow Lite Micro](../neural_networks/tflm.md) on-device so an externally trained network (for example trained with reinforcement learning in [Aerial Gym](https://ntnu-arl.github.io/aerial_gym_simulator/)) can be loaded as a tflite model and substituted for the multicopter controller for research and bench testing. It is not a replacement for the production controller stack. + ([PX4-Autopilot#24366](https://github.com/PX4/PX4-Autopilot/pull/24366)) ## Upgrade Guide +For users upgrading from v1.16, please take a moment to review the following before flying: + +1. **Re-check RC stick deadzones.** + The hardcoded 1 percent deadzone on RC channels 1 to 8 has been removed. If your transmitter has any centre-stick jitter, configure a per-channel deadzone explicitly via `RC_DZ` after upgrading, otherwise the vehicle may respond to small stick noise that v1.16 quietly ignored. + ([PX4-Autopilot#25502](https://github.com/PX4/PX4-Autopilot/pull/25502)) + +2. **Re-trim servos with the new `PWM_*_CENTER` parameters.** + The old `PWM_*_TRIM` servo trim parameters have been replaced by `PWM_*_CENTER` with asymmetric deflection. Trim values are not auto-migrated. Open the actuator configuration in QGC after upgrade and re-set the centre for each servo channel that previously used `PWM_*_TRIM`. + ([PX4-Autopilot#25897](https://github.com/PX4/PX4-Autopilot/pull/25897)) + +3. **Update your GCS or companion if it relies on MAVLink v1.** + [`MAV_PROTO_VER`](../advanced_config/parameter_reference.md#MAV_PROTO_VER) now defaults to `2`. MAVLink v1 is still available, but only as an explicit opt-in. If your ground station, telemetry radio, or companion computer link was implicitly relying on the v1 fallback, either update the GCS/companion to MAVLink v2 or set `MAV_PROTO_VER=1` on the affected channel. + ([PX4-Autopilot#25583](https://github.com/PX4/PX4-Autopilot/pull/25583)) + +4. **Migrate manual-control expo and deadzone parameters.** + `MPC_XY_MAN_EXPO`, `MPC_Z_MAN_EXPO`, and `MPC_YAW_MAN_EXPO` are removed and fall back to a fixed default. `MPC_HOLD_DZ` has been renamed to [`MAN_DEADZONE`](../advanced_config/parameter_reference.md#MAN_DEADZONE) and now applies globally across modes that allow a deadzone. If you previously tuned expo or hold deadzone, set [`MAN_DEADZONE`](../advanced_config/parameter_reference.md#MAN_DEADZONE) explicitly; expo customisation is no longer available. + +5. **Confirm barometer auto-calibration behaviour matches your setup.** + The new [`SENS_BAR_AUTOCAL`](../advanced_config/parameter_reference.md#SENS_BAR_AUTOCAL) parameter enables barometer offset calibration against GNSS height when GNSS is the height reference, and is **enabled by default**. This is the desired behaviour for typical outdoor flight; if you operate indoor or in heavily GNSS-degraded environments and want to keep baro offsets locked, disable `SENS_BAR_AUTOCAL`. + ([PX4-Autopilot#24859](https://github.com/PX4/PX4-Autopilot/pull/24859)) + +6. **Re-tune range finder range-aid if you depended on `EKF2_RNG_A_IGATE`.** + `EKF2_RNG_A_IGATE` has been removed as part of the EKF2 parameter-naming consistency refactor. Range-aid tuning now relies on the remaining `EKF2_RNG_A_*` parameters. The default [`EKF2_MIN_RNG`](../advanced_config/parameter_reference.md#EKF2_MIN_RNG) was also reduced from 0.1 m to 0.01 m. + ([PX4-Autopilot#25137](https://github.com/PX4/PX4-Autopilot/pull/25137), [PX4-Autopilot#25574](https://github.com/PX4/PX4-Autopilot/pull/25574)) + +7. **Verify magnetometer configuration.** + Magnetometer calibration is only allowed when at least one mag is available and enabled (priority not 0). If you previously disabled all mags via priority 0, you must enable at least one before running calibration. + ([PX4-Autopilot#25714](https://github.com/PX4/PX4-Autopilot/pull/25714)) + +8. **Check airframe selection.** + `SYS_AUTOSTART=0` is now treated the same as no valid airframe. If you relied on `SYS_AUTOSTART=0` for any custom workflow, select an explicit airframe. + ([PX4-Autopilot#25645](https://github.com/PX4/PX4-Autopilot/pull/25645)) + +9. **Update scripts and external tooling for renamed commander/termination interfaces.** + The `commander lockdown on` shell command is now `commander termination`. The `FORCE_FAILSAFE` action is now `TERMINATION`, and `manual_lockdown` is now `kill`. Update any startup scripts, test harnesses, or external tooling that calls these by name. + +10. **Migrate consumers of `battery_status.serial_number`.** + The `serial_number` field has moved from `battery_status` to a new `battery_info` uORB message. Any consumer (logger, GCS, companion software) reading the serial number from `battery_status` must subscribe to `battery_info` instead. + +11. **Remove `parameters_injected.xml` from custom build flows.** + `parameters_injected.xml` has been removed from the build system. If you maintained a board layer or downstream fork that referenced it, drop the reference. + ([PX4-Autopilot#25549](https://github.com/PX4/PX4-Autopilot/pull/25549)) + ## Other changes ### Hardware Support -- **[New Hardware]** boards: [MicoAir743-Lite FC](../flight_controller/micoair743-lite.md) -- **[New Hardware]** boards: [RadiolinkPIX6 FC](../flight_controller/radiolink_pix6.md) -- **[New Hardware]** boards: [AP-H743-R1 FC](../flight_controller/x-mav_ap-h743r1.md) +#### New Flight Controllers - +- [QGC Bootloader Update](../advanced_config/bootloader_update.md#qgc-bootloader-update-sys-bl-update) via the [`SYS_BL_UPDATE`](../advanced_config/parameter_reference.md#SYS_BL_UPDATE) parameter has been re-enabled after being broken for several releases. + ([PX4-Autopilot#25032](https://github.com/PX4/PX4-Autopilot/pull/25032)) +- Failsafe handling now lets the pilot take over from a degraded failsafe state. + ([PX4-Autopilot#26269](https://github.com/PX4/PX4-Autopilot/pull/26269)) +- Offboard to Position (hold) mode change is no longer entered without RC. + ([PX4-Autopilot#26391](https://github.com/PX4/PX4-Autopilot/pull/26391)) +- Motor failure detection uses more robust timeout checks. + ([PX4-Autopilot#25757](https://github.com/PX4/PX4-Autopilot/pull/25757)) +- New `battery_info` uORB message with serial number compatible with UAVCAN, MAVLink, and battery drivers; `battery_status.serial_number` is removed. +- UAVCAN battery: better remaining-time calculation ([PX4-Autopilot#25500](https://github.com/PX4/PX4-Autopilot/pull/25500)) and filter sample interval increased to 500 ms ([PX4-Autopilot#25454](https://github.com/PX4/PX4-Autopilot/pull/25454)). +- Battery instances are capped at 3 (loggable batteries also raised to 3). +- Remaining-flight-time failsafe disabled by default. ### Control - - -- [MC Neural Network Module](../advanced/neural_networks.md) +- Servo PWM gains center setting and asymmetric deflection (`PWM_*_CENTER`). + ([PX4-Autopilot#25897](https://github.com/PX4/PX4-Autopilot/pull/25897)) +- PWM center support extended to wheel and gimbal actuators. + ([PX4-Autopilot#26211](https://github.com/PX4/PX4-Autopilot/pull/26211)) +- Configurable board PWM frequency from Kconfig. + ([PX4-Autopilot#24787](https://github.com/PX4/PX4-Autopilot/pull/24787)) +- DShot telemetry refactored to the platform serial abstraction with RX/TX pin-swap support. +- UAVCAN ESC initialization no longer publishes random values when stopped. + ([PX4-Autopilot#25485](https://github.com/PX4/PX4-Autopilot/pull/25485)) +- UAVCAN bootloader watchdog pet during long flashes. + ([PX4-Autopilot#25523](https://github.com/PX4/PX4-Autopilot/pull/25523)) +- Control allocator enabled for spacecraft on v6x. + ([PX4-Autopilot#25276](https://github.com/PX4/PX4-Autopilot/pull/25276)) ### Estimation -- TBD - - +- Added [MicroStrain Inertial Sensors](../sensor/microstrain.md) driver support. + ([PX4-Autopilot#23858](https://github.com/PX4/PX4-Autopilot/pull/23858)) +- [MicroStrain Inertial Sensors](../sensor/microstrain.md) gain expanded aiding support. + ([PX4-Autopilot#25673](https://github.com/PX4/PX4-Autopilot/pull/25673)) +- Added [sbgECom INS driver](../sensor/sbgecom.md). + ([PX4-Autopilot#24137](https://github.com/PX4/PX4-Autopilot/pull/24137)) +- Added EULER-NAV Baro-Inertial AHRS driver. + ([PX4-Autopilot#24534](https://github.com/PX4/PX4-Autopilot/pull/24534)) +- Added QMC5883P compass driver. + ([PX4-Autopilot#25115](https://github.com/PX4/PX4-Autopilot/pull/25115)) +- Added ICM42688P IMU support on the Mamba F405 MK2 V2. + ([PX4-Autopilot#25047](https://github.com/PX4/PX4-Autopilot/pull/25047)) +- Added LightWare SF30/d binary protocol. + ([PX4-Autopilot#25570](https://github.com/PX4/PX4-Autopilot/pull/25570)) +- Airspeed calibration only saves the offset when the full procedure succeeds. + ([PX4-Autopilot#25412](https://github.com/PX4/PX4-Autopilot/pull/25412)) +- AirspeedSelector adds a synthetic airspeed option. +- IMU gyro: default angular-acceleration filter lowered from 30 Hz to 20 Hz. ### Simulation -- Overhaul rover simulation: - - Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107) - - Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113) - - Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117) +#### Gazebo -- [Simulation-in-Hardware (SIH)](../sim_sih/index.md#supported-vehicle-types) - - New simulation: MC Hexacopter X - - New simulation: Ackermann Rover +- Gazebo CMake linking is now version-agnostic across `gz-transport`, `gz-sim`, `gz-sensors`, and `gz-plugin`, removing the hard pin to Harmonic in the build glue. Harmonic remains the supported, CI-tested version; building against newer Gazebo releases (e.g. Jetty / v15) is up to the developer to install and verify locally. + ([PX4-Autopilot#25521](https://github.com/PX4/PX4-Autopilot/pull/25521)) +- [Rover simulation](../frames_rover/index.md#simulation) updated to match the current rover-control architecture. + ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) +- Gazebo bridge sensors can be selectively disabled. + ([PX4-Autopilot#25484](https://github.com/PX4/PX4-Autopilot/pull/25484)) +- Gimbal yaw fix and DDS attitude publisher in the Gazebo bridge. + ([PX4-Autopilot#25754](https://github.com/PX4/PX4-Autopilot/pull/25754)) +- `PX4_GZ_MODEL_POSE` for custom spawn pose. + ([PX4-Autopilot#24956](https://github.com/PX4/PX4-Autopilot/pull/24956)) +- Updated Gazebo 24.04 documentation. + ([PX4-Autopilot#25586](https://github.com/PX4/PX4-Autopilot/pull/25586)) + +#### Simulation-in-Hardware (SIH) + +- [SIH](../sim_sih/index.md#supported-vehicle-types) now supports Hexacopter X and Ackermann rovers. + ([PX4-Autopilot#25194](https://github.com/PX4/PX4-Autopilot/pull/25194), [PX4-Autopilot#25405](https://github.com/PX4/PX4-Autopilot/pull/25405)) +- HITL/SIH battery status now driven by battery configuration parameters. + ([PX4-Autopilot#24103](https://github.com/PX4/PX4-Autopilot/pull/24103)) ### Debug & Logging -- TBD +- `AirspeedValidated` promoted to a standard uORB topic. + ([PX4-Autopilot#25579](https://github.com/PX4/PX4-Autopilot/pull/25579)) +- `upload_log.py` can target a custom upload server via CLI argument. + ([PX4-Autopilot#25702](https://github.com/PX4/PX4-Autopilot/pull/25702)) +- ULog tooling can recover UTC timestamps even when `sensor_gps` is not present. + ([PX4-Autopilot#25534](https://github.com/PX4/PX4-Autopilot/pull/25534)) +- UAVCAN node status is now logged to uORB for debugging. + ([PX4-Autopilot#23890](https://github.com/PX4/PX4-Autopilot/pull/23890)) +- ULog file format documentation expanded. + ([PX4-Autopilot#25624](https://github.com/PX4/PX4-Autopilot/pull/25624)) -### Ethernet +### ROS 2 / uXRCE-DDS -- TBD +- [PX4 ROS 2 Control Interface](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral and longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fw-lateral-longitudinal-setpoint) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). +- [Simple index-based namespace (`UXRCE_DDS_NS_IDX`)](../middleware/uxrce_dds.md#customizing-the-namespace) for uXRCE-DDS. + ([PX4-Autopilot#25444](https://github.com/PX4/PX4-Autopilot/pull/25444)) +- Namespace support for the uXRCE-DDS client during firmware upload. + ([PX4-Autopilot#25291](https://github.com/PX4/PX4-Autopilot/pull/25291)) +- New DDS topics: `TransponderReport` (ADS-B) ([PX4-Autopilot#25652](https://github.com/PX4/PX4-Autopilot/pull/25652)), `landing_gear` command from external modes ([PX4-Autopilot#25496](https://github.com/PX4/PX4-Autopilot/pull/25496)), `Wind` topic with 1 Hz rate limit, gimbal device attitude status, and FW high-level setpoint/configuration interfaces. -### uXRCE-DDS / Zenoh / ROS2 +### ROS 2 / Zenoh -- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)). -- [UXRCE_DDS: Simple index based namespace (UXRCE_DDS_NS_IDX)](../middleware/uxrce_dds.md#customizing-the-namespace) -- [Zenoh (PX4 ROS 2 rmw_zenoh)](../middleware/zenoh.md) + + +The in-tree [Zenoh middleware](../middleware/zenoh.md) (added in v1.16) matures toward `rmw_zenoh` compatibility in v1.17. Most of this work landed as direct commits without PR numbers; the following list groups it by area: + +- **rmw_zenoh compatibility**: implement `rmw_zenoh` features in the Zenoh module, move ROS 2 Rmw attachment code to `rmw_attachment.h`, switch to CDRv1 to match ROS 2, set transport lease to 60 s to match ROS 2, omit timestamp attachment, experimental liveliness so the ROS 2 graph works. +- **Configuration and CLI**: auto-generate default Zenoh config from `dds_topics.yaml`, new Domain ID parameter (and move `gid` into Zenoh), Zenoh CLI improvements, instance selection and pub/sub deletion, copy the uXRCE config layout for Zenoh. +- **Boards**: Zenoh is now built into the default firmware on `px4/fmu-v6xrt` (`make px4_fmu-v6xrt_default`). On `px4/fmu-v6x` and SITL it ships as an opt-in `zenoh` build variant (`make px4_fmu-v6x_zenoh`, `make px4_sitl_zenoh`); the same opt-in `zenoh.px4board` is also provided for `auterion/fmu-v6s` and `auterion/fmu-v6x`. Zenoh is additionally compiled in by default on `nxp/mr-canhubk3`, `nxp/mr-tropic`, and `nxp/tropic-community`. +- **NuttX support**: update NuttX config for use with Zenoh; backport NuttX FMU-v6x config for Zenoh ([PX4-Autopilot#26213](https://github.com/PX4/PX4-Autopilot/pull/26213)). +- **SITL**: new `px4_sitl_zenoh` cmake variant, default to `127.0.0.1` on SITL/POSIX, autostart Zenoh in SITL when enabled, friendlier error message when scouting finds nothing, GCC/SITL compile fixes. +- **Robustness**: validate payload size before stack allocation, increase CDR safety margin, handle parsing errors and non-existing types in config, fix topic-name and datatype mapping, pubsub-factory datatype-naming fix, fix status `keyexpr` printf, prevent integer-conversion warnings in zenoh-pico, optimize memory usage with optional publish-on-matching. +- **Docs and OOM fixes (backport)**: [PX4-Autopilot#26053](https://github.com/PX4/PX4-Autopilot/pull/26053). +- **Submodule**: `zenoh-pico` updated. ### MAVLink -- TBD - - +- New multicopter flight mode: [Altitude Cruise](../flight_modes_mc/altitude_cruise.md). Like Altitude mode, but when the roll/pitch/yaw sticks are released the vehicle holds the current tilt and heading (rather than returning to level), letting it cruise at a steady velocity without constant stick input. Intended for long-distance flights where the same tilt is held for an extended period. The manual-control-loss failsafe can optionally be disabled for this mode by setting the corresponding bit in [`COM_RCL_EXCEPT`](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT); when doing so, configure the data-link-loss failsafe via [`NAV_DLL_ACT`](../advanced_config/parameter_reference.md#NAV_DLL_ACT) to avoid fly-aways. +- Stick library refactored: globally available, getter-based, expo computed on getter call; `FixedWingModeManager` now uses the Sticks library. +- Orbit mode: configurable max speed replaces the 10 m/s hardcode ([PX4-Autopilot#25192](https://github.com/PX4/PX4-Autopilot/pull/25192)) and `HeadingSmoothing` is applied to avoid step changes during the approach; documentation clarified ([PX4-Autopilot#25208](https://github.com/PX4/PX4-Autopilot/pull/25208)). +- MC PositionControl: switch out of goto setpoint immediately when receiving `trajectory_setpoint`. +- Hexarotor X added to SIH and to `ActuatorEffectivenessRotorsTest`. +- `MC_RATE*` parameter metadata unified. + ([PX4-Autopilot#25133](https://github.com/PX4/PX4-Autopilot/pull/25133)) ### VTOL -- TBD +- Fixed VTOL stuck after back-transition in Mission Fast RTL. +- VTOL takeoff requires relaxed position only during the fixed-wing phase; on completion of takeoff, the state is forced to Loiter. +- VTOL airspeed measurement handling centralized. +- [PX4 ROS 2 Control Interface](../ros2/px4_ros2_control_interface.md#controlling-a-vtol) can command VTOL transitions from external modes. ### Fixed-wing -- [Fixed Wing Takeoff mode](../flight_modes_fw/takeoff.md) will now keep climbing with level wings on position loss. - A target takeoff waypoint can be set to control takeoff course and loiter altitude. ([PX4-Autopilot#25083](https://github.com/PX4/PX4-Autopilot/pull/25083)). -- Automatically suppress angular rate oscillations using [Gain compression](../features_fw/gain_compression.md). ([PX4-Autopilot#25840: FW rate control: add gain compression algorithm](https://github.com/PX4/PX4-Autopilot/pull/25840)) +- [Fixed Wing Takeoff mode](../flight_modes_fw/takeoff.md) keeps climbing with level wings on navigation loss and can use the takeoff waypoint latitude and longitude to define the loiter position. + ([PX4-Autopilot#25226](https://github.com/PX4/PX4-Autopilot/pull/25226)) +- Reworked fixed-wing high-level control exposes clean lateral and longitudinal control interfaces for external integrations. +- FW Attitude Controller wheel controller rework. +- FW Autotune: identification maneuver auto-ramps the 1 Hz amplitude until R/P/Y rates of 0.8/0.5/0.5 rad/s are reached, then scales the identification signal accordingly. +- TECS hardening: NaN protection on airspeed and altitude inputs. ### Rover -- Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)). -- Add support for [Apps & API](../flight_modes_rover/api.md) including [Rover Setpoints](../ros2/px4_ros2_control_interface.md#rover-setpoints) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)). -- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details). +- Removed deprecated rover module. +- Added [Apps & API](../flight_modes_rover/api.md) support including [Rover Setpoints](../ros2/px4_ros2_control_interface.md#rover-setpoints). +- [Rover simulation](../frames_rover/index.md#simulation) updated to match the reworked rover architecture. + ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) +- Continued per-vehicle (Ackermann/differential/mecanum) restructuring with separated actuator control, position-control updates, mode-management centralization, and module split into folders. +- New stick-input scaling parameters. + ([PX4-Autopilot#25427](https://github.com/PX4/PX4-Autopilot/pull/25427)) +- Improved rover hold-position logic. + ([PX4-Autopilot#25466](https://github.com/PX4/PX4-Autopilot/pull/25466)) +- `RX_MAX_THR_YAW_R` replaced by `RO_YAW_RATE_CORR`. +- Manual yaw-rate input: exponential scaling. +- Comprehensive [Rover API documentation](../flight_modes_rover/api.md). + ([PX4-Autopilot#25499](https://github.com/PX4/PX4-Autopilot/pull/25499)) +- MR-CANHUBK344 NXP B3RB rover platform. + ([PX4-Autopilot#23897](https://github.com/PX4/PX4-Autopilot/pull/23897)) +- Aion Robotics R1 Rover airframe (`50001`) marked discontinued. -### ROS 2 +### Safety / Commander -- TBD +- Failure injection refactored into its own class; `failure motor off -i ` now requires `CA_FAILURE_MODE` to be set. See [motor failure injection and detection](../debug/failure_injection.md). + ([PX4-Autopilot#25756](https://github.com/PX4/PX4-Autopilot/pull/25756)) +- Naming for clarity: `FORCE_FAILSAFE` renamed to `TERMINATION`; `commander lockdown on` renamed to `commander termination`; `manual_lockdown` renamed to `kill`; `ACTION_TERMINATE` renamed to `ACTION_TERMINATION`. +- New RC termination switch with PWM-input default for ATS-based flight termination. + ([PX4-Autopilot#25209](https://github.com/PX4/PX4-Autopilot/pull/25209)) +- Commander never overrides a user-intended termination (with unit test). +- Remaining-flight-time failsafe disabled by default. +- Home position is not reset if landed during an uncompleted mission. + ([PX4-Autopilot#24902](https://github.com/PX4/PX4-Autopilot/pull/24902)) +- Off-track mission landing fix. + ([PX4-Autopilot#25725](https://github.com/PX4/PX4-Autopilot/pull/25725)) + +### Infrastructure + +- `parameters_injected.xml` removed from the build system. + ([PX4-Autopilot#25549](https://github.com/PX4/PX4-Autopilot/pull/25549)) +- [QGC Bootloader Update](../advanced_config/bootloader_update.md#qgc-bootloader-update-sys-bl-update) via `SYS_BL_UPDATE` restored. + ([PX4-Autopilot#25032](https://github.com/PX4/PX4-Autopilot/pull/25032)) +- NuttX submodule updates: dcache fix and semaphore-holder-list fix. +- ITCM checker added in CI; ITCM mapping updated for v6xRT and Tropic-Community. +- Flash savings on KakuteH7 encrypted-logs variants and on selected ARK targets. +- Spacecraft tooling for Commander and `VehicleStatus`. + ([PX4-Autopilot#24716](https://github.com/PX4/PX4-Autopilot/pull/24716)) diff --git a/docs/en/releases/main.md b/docs/en/releases/main.md index 34cee1ed5f..844541f385 100644 --- a/docs/en/releases/main.md +++ b/docs/en/releases/main.md @@ -100,7 +100,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). diff --git a/docs/en/ros2/px4_ros2_control_interface.md b/docs/en/ros2/px4_ros2_control_interface.md index 6032e6d2d5..8a74983a6b 100644 --- a/docs/en/ros2/px4_ros2_control_interface.md +++ b/docs/en/ros2/px4_ros2_control_interface.md @@ -347,7 +347,7 @@ The used types also define the compatibility with different vehicle types. The following sections provide a list of supported setpoint types: - [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): Smooth position and (optionally) heading control -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics +- [FwLateralLongitudinalSetpointType](#fw-lateral-longitudinal-setpoint): Direct control of lateral and longitudinal fixed wing dynamics - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints - [Rover Setpoints](#rover-setpoints): Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering). @@ -414,7 +414,7 @@ _goto_setpoint->update( max_heading_rate_rad_s); ``` -#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) +#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) {#fw-lateral-longitudinal-setpoint} @@ -597,7 +597,7 @@ An example for a rover specific drive mode using the `RoverSpeedAttitudeSetpoint To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: - Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`MulticopterGotoSetpointType`](#go-to-setpoint-multicoptergotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). -- Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype). +- Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fw-lateral-longitudinal-setpoint). As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required. diff --git a/integrationtests/python_src/px4_it/mavros/__init__.py b/integrationtests/python_src/px4_it/mavros/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py deleted file mode 100755 index 4432e466e7..0000000000 --- a/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py +++ /dev/null @@ -1,154 +0,0 @@ -#!/usr/bin/env python3 -#*************************************************************************** -# -# Copyright (c) 2015 PX4 Development Team. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 3. Neither the name PX4 nor the names of its contributors may be -# used to endorse or promote products derived from this software -# without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -#***************************************************************************/ - -# -# @author Andreas Antener -# - -PKG = 'px4' - -import rospy -from geometry_msgs.msg import Quaternion, Vector3 -from mavros_msgs.msg import AttitudeTarget -from mavros_test_common import MavrosTestCommon -from pymavlink import mavutil -from std_msgs.msg import Header -from threading import Thread -from tf.transformations import quaternion_from_euler - - -class MavrosOffboardAttctlTest(MavrosTestCommon): - """ - Tests flying in offboard control by sending attitude and thrust setpoints - via MAVROS. - - For the test to be successful it needs to cross a certain boundary in time. - """ - - def setUp(self): - super(MavrosOffboardAttctlTest, self).setUp() - - self.att = AttitudeTarget() - - self.att_setpoint_pub = rospy.Publisher( - 'mavros/setpoint_raw/attitude', AttitudeTarget, queue_size=1) - - # send setpoints in separate thread to better prevent failsafe - self.att_thread = Thread(target=self.send_att, args=()) - self.att_thread.daemon = True - self.att_thread.start() - - def tearDown(self): - super(MavrosOffboardAttctlTest, self).tearDown() - - # - # Helper methods - # - def send_att(self): - rate = rospy.Rate(10) # Hz - self.att.body_rate = Vector3() - self.att.header = Header() - self.att.header.frame_id = "base_footprint" - self.att.orientation = Quaternion(*quaternion_from_euler(-0.25, 0.15, - 0)) - self.att.thrust = 0.7 - self.att.type_mask = 7 # ignore body rate - - while not rospy.is_shutdown(): - self.att.header.stamp = rospy.Time.now() - self.att_setpoint_pub.publish(self.att) - try: # prevent garbage in console output when thread is killed - rate.sleep() - except rospy.ROSInterruptException: - pass - - # - # Test method - # - def test_attctl(self): - """Test offboard attitude control""" - # boundary to cross - boundary_x = 200 - boundary_y = 100 - boundary_z = 20 - - # make sure the simulation is ready to start the mission - self.wait_for_topics(60) - self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, - 10, -1) - - self.log_topic_vars() - self.set_mode("OFFBOARD", 5) - self.set_arm(True, 5) - - rospy.loginfo("run mission") - rospy.loginfo("attempting to cross boundary | x: {0}, y: {1}, z: {2}". - format(boundary_x, boundary_y, boundary_z)) - # does it cross expected boundaries in 'timeout' seconds? - timeout = 90 # (int) seconds - loop_freq = 2 # Hz - rate = rospy.Rate(loop_freq) - crossed = False - for i in range(timeout * loop_freq): - if (self.local_position.pose.position.x > boundary_x and - self.local_position.pose.position.y > boundary_y and - self.local_position.pose.position.z > boundary_z): - rospy.loginfo("boundary crossed | seconds: {0} of {1}".format( - i / loop_freq, timeout)) - crossed = True - break - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(crossed, ( - "took too long to cross boundaries | current position x: {0:.2f}, y: {1:.2f}, z: {2:.2f} | timeout(seconds): {3}". - format(self.local_position.pose.position.x, - self.local_position.pose.position.y, - self.local_position.pose.position.z, timeout))) - - self.set_mode("AUTO.LAND", 5) - self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, - 90, 0) - self.set_arm(False, 5) - - -if __name__ == '__main__': - import rostest - rospy.init_node('test_node', anonymous=True) - - rostest.rosrun(PKG, 'mavros_offboard_attctl_test', - MavrosOffboardAttctlTest) diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py deleted file mode 100755 index 8e88bf608b..0000000000 --- a/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py +++ /dev/null @@ -1,188 +0,0 @@ -#!/usr/bin/env python3 -#*************************************************************************** -# -# Copyright (c) 2015 PX4 Development Team. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 3. Neither the name PX4 nor the names of its contributors may be -# used to endorse or promote products derived from this software -# without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -#***************************************************************************/ - -# -# @author Andreas Antener -# - -PKG = 'px4' - -import rospy -import math -import numpy as np -from geometry_msgs.msg import PoseStamped, Quaternion -from mavros_msgs.msg import ParamValue -from mavros_test_common import MavrosTestCommon -from pymavlink import mavutil -from std_msgs.msg import Header -from threading import Thread -from tf.transformations import quaternion_from_euler - - -class MavrosOffboardPosctlTest(MavrosTestCommon): - """ - Tests flying a path in offboard control by sending position setpoints - via MAVROS. - - For the test to be successful it needs to reach all setpoints in a certain time. - - FIXME: add flight path assertion (needs transformation from ROS frame to NED) - """ - - def setUp(self): - super(MavrosOffboardPosctlTest, self).setUp() - - self.pos = PoseStamped() - self.radius = 1 - - self.pos_setpoint_pub = rospy.Publisher( - 'mavros/setpoint_position/local', PoseStamped, queue_size=1) - - # send setpoints in separate thread to better prevent failsafe - self.pos_thread = Thread(target=self.send_pos, args=()) - self.pos_thread.daemon = True - self.pos_thread.start() - - def tearDown(self): - super(MavrosOffboardPosctlTest, self).tearDown() - - # - # Helper methods - # - def send_pos(self): - rate = rospy.Rate(10) # Hz - self.pos.header = Header() - self.pos.header.frame_id = "base_footprint" - - while not rospy.is_shutdown(): - self.pos.header.stamp = rospy.Time.now() - self.pos_setpoint_pub.publish(self.pos) - try: # prevent garbage in console output when thread is killed - rate.sleep() - except rospy.ROSInterruptException: - pass - - def is_at_position(self, x, y, z, offset): - """offset: meters""" - rospy.logdebug( - "current position | x:{0:.2f}, y:{1:.2f}, z:{2:.2f}".format( - self.local_position.pose.position.x, self.local_position.pose. - position.y, self.local_position.pose.position.z)) - - desired = np.array((x, y, z)) - pos = np.array((self.local_position.pose.position.x, - self.local_position.pose.position.y, - self.local_position.pose.position.z)) - return np.linalg.norm(desired - pos) < offset - - def reach_position(self, x, y, z, timeout): - """timeout(int): seconds""" - # set a position setpoint - self.pos.pose.position.x = x - self.pos.pose.position.y = y - self.pos.pose.position.z = z - rospy.loginfo( - "attempting to reach position | x: {0}, y: {1}, z: {2} | current position x: {3:.2f}, y: {4:.2f}, z: {5:.2f}". - format(x, y, z, self.local_position.pose.position.x, - self.local_position.pose.position.y, - self.local_position.pose.position.z)) - - # For demo purposes we will lock yaw/heading to north. - yaw_degrees = 0 # North - yaw = math.radians(yaw_degrees) - quaternion = quaternion_from_euler(0, 0, yaw) - self.pos.pose.orientation = Quaternion(*quaternion) - - # does it reach the position in 'timeout' seconds? - loop_freq = 2 # Hz - rate = rospy.Rate(loop_freq) - reached = False - for i in range(timeout * loop_freq): - if self.is_at_position(self.pos.pose.position.x, - self.pos.pose.position.y, - self.pos.pose.position.z, self.radius): - rospy.loginfo("position reached | seconds: {0} of {1}".format( - i / loop_freq, timeout)) - reached = True - break - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(reached, ( - "took too long to get to position | current position x: {0:.2f}, y: {1:.2f}, z: {2:.2f} | timeout(seconds): {3}". - format(self.local_position.pose.position.x, - self.local_position.pose.position.y, - self.local_position.pose.position.z, timeout))) - - # - # Test method - # - def test_posctl(self): - """Test offboard position control""" - - # make sure the simulation is ready to start the mission - self.wait_for_topics(60) - self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, - 10, -1) - - self.log_topic_vars() - # exempting failsafe from lost RC to allow offboard - rcl_except = ParamValue(1<<2, 0.0) - self.set_param("COM_RCL_EXCEPT", rcl_except, 5) - self.set_mode("OFFBOARD", 5) - self.set_arm(True, 5) - - rospy.loginfo("run mission") - positions = ((0, 0, 0), (50, 50, 20), (50, -50, 20), (-50, -50, 20), - (0, 0, 20)) - - for i in range(len(positions)): - self.reach_position(positions[i][0], positions[i][1], - positions[i][2], 30) - - self.set_mode("AUTO.LAND", 5) - self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, - 45, 0) - self.set_arm(False, 5) - - -if __name__ == '__main__': - import rostest - rospy.init_node('test_node', anonymous=True) - - rostest.rosrun(PKG, 'mavros_offboard_posctl_test', - MavrosOffboardPosctlTest) diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_yawrate_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_yawrate_test.py deleted file mode 100755 index 88b646a19b..0000000000 --- a/integrationtests/python_src/px4_it/mavros/mavros_offboard_yawrate_test.py +++ /dev/null @@ -1,174 +0,0 @@ -#!/usr/bin/env python3 -#*************************************************************************** -# -# Copyright (c) 2020 PX4 Development Team. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 3. Neither the name PX4 nor the names of its contributors may be -# used to endorse or promote products derived from this software -# without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -#***************************************************************************/ -# -# @author Pedro Roque -# - -PKG = 'px4' - -import rospy -from geometry_msgs.msg import Quaternion, Vector3 -from mavros_msgs.msg import AttitudeTarget -from mavros_test_common import MavrosTestCommon -from pymavlink import mavutil -from std_msgs.msg import Header -from threading import Thread -from tf.transformations import quaternion_from_euler - - -class MavrosOffboardYawrateTest(MavrosTestCommon): - """ - Tests flying in offboard control by sending a Roll Pitch Yawrate Thrust (RPYrT) - as attitude setpoint. - - For the test to be successful it needs to achieve a desired yawrate and height. - """ - - def setUp(self): - super(MavrosOffboardYawrateTest, self).setUp() - - self.att = AttitudeTarget() - - self.att_setpoint_pub = rospy.Publisher( - 'mavros/setpoint_raw/attitude', AttitudeTarget, queue_size=1) - - # send setpoints in separate thread to better prevent failsafe - self.att_thread = Thread(target=self.send_att, args=()) - self.att_thread.daemon = True - self.att_thread.start() - - # desired yawrate target - self.des_yawrate = 0.1 - self.yawrate_tol = 0.02 - - def tearDown(self): - super(MavrosOffboardYawrateTest, self).tearDown() - - # - # Helper methods - # - def send_att(self): - rate = rospy.Rate(10) # Hz - self.att.body_rate = Vector3() - self.att.header = Header() - self.att.header.frame_id = "base_footprint" - self.att.orientation = self.local_position.pose.orientation - - self.att.body_rate.x = 0 - self.att.body_rate.y = 0 - self.att.body_rate.z = self.des_yawrate - - self.att.thrust = 0.59 - - self.att.type_mask = 3 # ignore roll and pitch rate - - while not rospy.is_shutdown(): - self.att.header.stamp = rospy.Time.now() - self.att_setpoint_pub.publish(self.att) - try: # prevent garbage in console output when thread is killed - rate.sleep() - except rospy.ROSInterruptException: - pass - - # - # Test method - # - def test_attctl(self): - """Test offboard yawrate control""" - - # boundary to cross - # Stay leveled, go up, and test yawrate - boundary_x = 5 - boundary_y = 5 - boundary_z = 10 - - - # make sure the simulation is ready to start the mission - self.wait_for_topics(60) - self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, - 10, -1) - - self.log_topic_vars() - self.set_arm(True, 5) - self.set_mode("OFFBOARD", 5) - rospy.loginfo("run mission") - rospy.loginfo("attempting to cross boundary | z: {2} , stay within x: {0} y: {1} \n and achieve {3} yawrate". - format(boundary_x, boundary_y, boundary_z, self.des_yawrate)) - - # does it cross expected boundaries in 'timeout' seconds? - timeout = 90 # (int) seconds - loop_freq = 2 # Hz - rate = rospy.Rate(loop_freq) - crossed = False - for i in range(timeout * loop_freq): - if (self.local_position.pose.position.x < boundary_x and - self.local_position.pose.position.x > -boundary_x and - self.local_position.pose.position.y < boundary_y and - self.local_position.pose.position.y > -boundary_y and - self.local_position.pose.position.z > boundary_z and - abs(self.imu_data.angular_velocity.z - self.des_yawrate) < self.yawrate_tol): - rospy.loginfo("Test successful. Final altitude and yawrate achieved") - crossed = True - break - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(crossed, ( - "took too long to finish test | current position x: {0:.2f}, y: {1:.2f}, z: {2:.2f} \n " \ - " | current att qx: {3:.2f}, qy: {4:.2f}, qz: {5:.2f} qw: {6:.2f}, yr: {7:.2f}| timeout(seconds): {8}". - format(self.local_position.pose.position.x, - self.local_position.pose.position.y, - self.local_position.pose.position.z, - self.imu_data.orientation.x, - self.imu_data.orientation.y, - self.imu_data.orientation.z, - self.imu_data.orientation.w, - self.imu_data.angular_velocity.z, - timeout))) - - self.set_mode("AUTO.LAND", 5) - self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, - 90, 0) - self.set_arm(False, 5) - - -if __name__ == '__main__': - import rostest - rospy.init_node('test_node', anonymous=True) - - rostest.rosrun(PKG, 'mavros_offboard_yawrate_test', - MavrosOffboardYawrateTest) diff --git a/integrationtests/python_src/px4_it/mavros/mavros_test_common.py b/integrationtests/python_src/px4_it/mavros/mavros_test_common.py deleted file mode 100644 index ee5a95d438..0000000000 --- a/integrationtests/python_src/px4_it/mavros/mavros_test_common.py +++ /dev/null @@ -1,458 +0,0 @@ -#!/usr/bin/env python3 - -import unittest -import rospy -import math -from geometry_msgs.msg import PoseStamped -from mavros_msgs.msg import Altitude, ExtendedState, HomePosition, ParamValue, State, \ - WaypointList -from mavros_msgs.srv import CommandBool, ParamGet, ParamSet, SetMode, SetModeRequest, WaypointClear, \ - WaypointPush -from pymavlink import mavutil -from sensor_msgs.msg import NavSatFix, Imu - - -class MavrosTestCommon(unittest.TestCase): - def __init__(self, *args): - super(MavrosTestCommon, self).__init__(*args) - - def setUp(self): - self.altitude = Altitude() - self.extended_state = ExtendedState() - self.global_position = NavSatFix() - self.imu_data = Imu() - self.home_position = HomePosition() - self.local_position = PoseStamped() - self.mission_wp = WaypointList() - self.state = State() - self.mav_type = None - - self.sub_topics_ready = { - key: False - for key in [ - 'alt', 'ext_state', 'global_pos', 'home_pos', 'local_pos', - 'mission_wp', 'state', 'imu' - ] - } - - # ROS services - service_timeout = 30 - rospy.loginfo("waiting for ROS services") - try: - rospy.wait_for_service('mavros/param/get', service_timeout) - rospy.wait_for_service('mavros/param/set', service_timeout) - rospy.wait_for_service('mavros/cmd/arming', service_timeout) - rospy.wait_for_service('mavros/mission/push', service_timeout) - rospy.wait_for_service('mavros/mission/clear', service_timeout) - rospy.wait_for_service('mavros/set_mode', service_timeout) - rospy.loginfo("ROS services are up") - except rospy.ROSException: - self.fail("failed to connect to services") - self.get_param_srv = rospy.ServiceProxy('mavros/param/get', ParamGet) - self.set_param_srv = rospy.ServiceProxy('mavros/param/set', ParamSet) - self.set_arming_srv = rospy.ServiceProxy('mavros/cmd/arming', - CommandBool) - self.set_mode_srv = rospy.ServiceProxy('mavros/set_mode', SetMode) - self.wp_clear_srv = rospy.ServiceProxy('mavros/mission/clear', - WaypointClear) - self.wp_push_srv = rospy.ServiceProxy('mavros/mission/push', - WaypointPush) - - # ROS subscribers - self.alt_sub = rospy.Subscriber('mavros/altitude', Altitude, - self.altitude_callback) - self.ext_state_sub = rospy.Subscriber('mavros/extended_state', - ExtendedState, - self.extended_state_callback) - self.global_pos_sub = rospy.Subscriber('mavros/global_position/global', - NavSatFix, - self.global_position_callback) - self.imu_data_sub = rospy.Subscriber('mavros/imu/data', - Imu, - self.imu_data_callback) - self.home_pos_sub = rospy.Subscriber('mavros/home_position/home', - HomePosition, - self.home_position_callback) - self.local_pos_sub = rospy.Subscriber('mavros/local_position/pose', - PoseStamped, - self.local_position_callback) - self.mission_wp_sub = rospy.Subscriber( - 'mavros/mission/waypoints', WaypointList, self.mission_wp_callback) - self.state_sub = rospy.Subscriber('mavros/state', State, - self.state_callback) - - def tearDown(self): - self.log_topic_vars() - - # - # Callback functions - # - def altitude_callback(self, data): - self.altitude = data - - # amsl has been observed to be nan while other fields are valid - if not self.sub_topics_ready['alt'] and not math.isnan(data.amsl): - self.sub_topics_ready['alt'] = True - - def extended_state_callback(self, data): - if self.extended_state.vtol_state != data.vtol_state: - rospy.loginfo("VTOL state changed from {0} to {1}".format( - mavutil.mavlink.enums['MAV_VTOL_STATE'] - [self.extended_state.vtol_state].name, mavutil.mavlink.enums[ - 'MAV_VTOL_STATE'][data.vtol_state].name)) - - if self.extended_state.landed_state != data.landed_state: - rospy.loginfo("landed state changed from {0} to {1}".format( - mavutil.mavlink.enums['MAV_LANDED_STATE'] - [self.extended_state.landed_state].name, mavutil.mavlink.enums[ - 'MAV_LANDED_STATE'][data.landed_state].name)) - - self.extended_state = data - - if not self.sub_topics_ready['ext_state']: - self.sub_topics_ready['ext_state'] = True - - def global_position_callback(self, data): - self.global_position = data - - if not self.sub_topics_ready['global_pos']: - self.sub_topics_ready['global_pos'] = True - - def imu_data_callback(self, data): - self.imu_data = data - - if not self.sub_topics_ready['imu']: - self.sub_topics_ready['imu'] = True - - def home_position_callback(self, data): - self.home_position = data - - if not self.sub_topics_ready['home_pos']: - self.sub_topics_ready['home_pos'] = True - - def local_position_callback(self, data): - self.local_position = data - - if not self.sub_topics_ready['local_pos']: - self.sub_topics_ready['local_pos'] = True - - def mission_wp_callback(self, data): - if self.mission_wp.current_seq != data.current_seq: - rospy.loginfo("current mission waypoint sequence updated: {0}". - format(data.current_seq)) - - self.mission_wp = data - - if not self.sub_topics_ready['mission_wp']: - self.sub_topics_ready['mission_wp'] = True - - def state_callback(self, data): - if self.state.armed != data.armed: - rospy.loginfo("armed state changed from {0} to {1}".format( - self.state.armed, data.armed)) - - if self.state.connected != data.connected: - rospy.loginfo("connected changed from {0} to {1}".format( - self.state.connected, data.connected)) - - if self.state.mode != data.mode: - rospy.loginfo("mode changed from {0} to {1}".format( - self.state.mode, data.mode)) - - if self.state.system_status != data.system_status: - rospy.loginfo("system_status changed from {0} to {1}".format( - mavutil.mavlink.enums['MAV_STATE'][ - self.state.system_status].name, mavutil.mavlink.enums[ - 'MAV_STATE'][data.system_status].name)) - - self.state = data - - # mavros publishes a disconnected state message on init - if not self.sub_topics_ready['state'] and data.connected: - self.sub_topics_ready['state'] = True - - # - # Helper methods - # - def set_arm(self, arm, timeout): - """arm: True to arm or False to disarm, timeout(int): seconds""" - rospy.loginfo("setting FCU arm: {0}".format(arm)) - old_arm = self.state.armed - loop_freq = 1 # Hz - rate = rospy.Rate(loop_freq) - arm_set = False - for i in range(timeout * loop_freq): - if self.state.armed == arm: - arm_set = True - rospy.loginfo("set arm success | seconds: {0} of {1}".format( - i / loop_freq, timeout)) - break - else: - try: - res = self.set_arming_srv(arm) - if not res.success: - rospy.logerr("failed to send arm command") - except rospy.ServiceException as e: - rospy.logerr(e) - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(arm_set, ( - "failed to set arm | new arm: {0}, old arm: {1} | timeout(seconds): {2}". - format(arm, old_arm, timeout))) - - def set_mode(self, mode, timeout): - """mode: PX4 mode string, timeout(int): seconds""" - rospy.loginfo("setting FCU mode: {0}".format(mode)) - old_mode = self.state.mode - loop_freq = 1 # Hz - rate = rospy.Rate(loop_freq) - mode_set = False - for i in range(timeout * loop_freq): - if self.state.mode == mode: - mode_set = True - rospy.loginfo("set mode success | seconds: {0} of {1}".format( - i / loop_freq, timeout)) - break - else: - try: - res = self.set_mode_srv(0, mode) # 0 is custom mode - if not res.mode_sent: - rospy.logerr("failed to send mode command") - except rospy.ServiceException as e: - rospy.logerr(e) - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(mode_set, ( - "failed to set mode | new mode: {0}, old mode: {1} | timeout(seconds): {2}". - format(mode, old_mode, timeout))) - - def set_param(self, param_id, param_value, timeout): - """param: PX4 param string, ParamValue, timeout(int): seconds""" - if param_value.integer != 0: - value = param_value.integer - else: - value = param_value.real - rospy.loginfo("setting PX4 parameter: {0} with value {1}". - format(param_id, value)) - loop_freq = 1 # Hz - rate = rospy.Rate(loop_freq) - param_set = False - for i in range(timeout * loop_freq): - try: - res = self.set_param_srv(param_id, param_value) - if res.success: - rospy.loginfo("param {0} set to {1} | seconds: {2} of {3}". - format(param_id, value, i / loop_freq, timeout)) - break - except rospy.ServiceException as e: - rospy.logerr(e) - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(res.success, ( - "failed to set param | param_id: {0}, param_value: {1} | timeout(seconds): {2}". - format(param_id, value, timeout))) - - def wait_for_topics(self, timeout): - """wait for simulation to be ready, make sure we're getting topic info - from all topics by checking dictionary of flag values set in callbacks, - timeout(int): seconds""" - rospy.loginfo("waiting for subscribed topics to be ready") - loop_freq = 1 # Hz - rate = rospy.Rate(loop_freq) - simulation_ready = False - for i in range(timeout * loop_freq): - if all(value for value in self.sub_topics_ready.values()): - simulation_ready = True - rospy.loginfo("simulation topics ready | seconds: {0} of {1}". - format(i / loop_freq, timeout)) - break - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(simulation_ready, ( - "failed to hear from all subscribed simulation topics | topic ready flags: {0} | timeout(seconds): {1}". - format(self.sub_topics_ready, timeout))) - - def wait_for_landed_state(self, desired_landed_state, timeout, index): - rospy.loginfo("waiting for landed state | state: {0}, index: {1}". - format(mavutil.mavlink.enums['MAV_LANDED_STATE'][ - desired_landed_state].name, index)) - loop_freq = 10 # Hz - rate = rospy.Rate(loop_freq) - landed_state_confirmed = False - for i in range(timeout * loop_freq): - if self.extended_state.landed_state == desired_landed_state: - landed_state_confirmed = True - rospy.loginfo("landed state confirmed | seconds: {0} of {1}". - format(i / loop_freq, timeout)) - break - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(landed_state_confirmed, ( - "landed state not detected | desired: {0}, current: {1} | index: {2}, timeout(seconds): {3}". - format(mavutil.mavlink.enums['MAV_LANDED_STATE'][ - desired_landed_state].name, mavutil.mavlink.enums[ - 'MAV_LANDED_STATE'][self.extended_state.landed_state].name, - index, timeout))) - - def wait_for_vtol_state(self, transition, timeout, index): - """Wait for VTOL transition, timeout(int): seconds""" - rospy.loginfo( - "waiting for VTOL transition | transition: {0}, index: {1}".format( - mavutil.mavlink.enums['MAV_VTOL_STATE'][ - transition].name, index)) - loop_freq = 10 # Hz - rate = rospy.Rate(loop_freq) - transitioned = False - for i in range(timeout * loop_freq): - if transition == self.extended_state.vtol_state: - rospy.loginfo("transitioned | seconds: {0} of {1}".format( - i / loop_freq, timeout)) - transitioned = True - break - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(transitioned, ( - "transition not detected | desired: {0}, current: {1} | index: {2} timeout(seconds): {3}". - format(mavutil.mavlink.enums['MAV_VTOL_STATE'][transition].name, - mavutil.mavlink.enums['MAV_VTOL_STATE'][ - self.extended_state.vtol_state].name, index, timeout))) - - def clear_wps(self, timeout): - """timeout(int): seconds""" - loop_freq = 1 # Hz - rate = rospy.Rate(loop_freq) - wps_cleared = False - for i in range(timeout * loop_freq): - if not self.mission_wp.waypoints: - wps_cleared = True - rospy.loginfo("clear waypoints success | seconds: {0} of {1}". - format(i / loop_freq, timeout)) - break - else: - try: - res = self.wp_clear_srv() - if not res.success: - rospy.logerr("failed to send waypoint clear command") - except rospy.ServiceException as e: - rospy.logerr(e) - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(wps_cleared, ( - "failed to clear waypoints | timeout(seconds): {0}".format(timeout) - )) - - def send_wps(self, waypoints, timeout): - """waypoints, timeout(int): seconds""" - rospy.loginfo("sending mission waypoints") - if self.mission_wp.waypoints: - rospy.loginfo("FCU already has mission waypoints") - - loop_freq = 1 # Hz - rate = rospy.Rate(loop_freq) - wps_sent = False - wps_verified = False - for i in range(timeout * loop_freq): - if not wps_sent: - try: - res = self.wp_push_srv(start_index=0, waypoints=waypoints) - wps_sent = res.success - if wps_sent: - rospy.loginfo("waypoints successfully transferred") - except rospy.ServiceException as e: - rospy.logerr(e) - else: - if len(waypoints) == len(self.mission_wp.waypoints): - rospy.loginfo("number of waypoints transferred: {0}". - format(len(waypoints))) - wps_verified = True - - if wps_sent and wps_verified: - rospy.loginfo("send waypoints success | seconds: {0} of {1}". - format(i / loop_freq, timeout)) - break - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(( - wps_sent and wps_verified - ), "mission could not be transferred and verified | timeout(seconds): {0}". - format(timeout)) - - def wait_for_mav_type(self, timeout): - """Wait for MAV_TYPE parameter, timeout(int): seconds""" - rospy.loginfo("waiting for MAV_TYPE") - loop_freq = 1 # Hz - rate = rospy.Rate(loop_freq) - res = False - for i in range(timeout * loop_freq): - try: - res = self.get_param_srv('MAV_TYPE') - if res.success: - self.mav_type = res.value.integer - rospy.loginfo( - "MAV_TYPE received | type: {0} | seconds: {1} of {2}". - format(mavutil.mavlink.enums['MAV_TYPE'][self.mav_type] - .name, i / loop_freq, timeout)) - break - except rospy.ServiceException as e: - rospy.logerr(e) - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue(res.success, ( - "MAV_TYPE param get failed | timeout(seconds): {0}".format(timeout) - )) - - def log_topic_vars(self): - """log the state of topic variables""" - rospy.loginfo("========================") - rospy.loginfo("===== topic values =====") - rospy.loginfo("========================") - rospy.loginfo("altitude:\n{}".format(self.altitude)) - rospy.loginfo("========================") - rospy.loginfo("extended_state:\n{}".format(self.extended_state)) - rospy.loginfo("========================") - rospy.loginfo("global_position:\n{}".format(self.global_position)) - rospy.loginfo("========================") - rospy.loginfo("home_position:\n{}".format(self.home_position)) - rospy.loginfo("========================") - rospy.loginfo("local_position:\n{}".format(self.local_position)) - rospy.loginfo("========================") - rospy.loginfo("mission_wp:\n{}".format(self.mission_wp)) - rospy.loginfo("========================") - rospy.loginfo("state:\n{}".format(self.state)) - rospy.loginfo("========================") diff --git a/integrationtests/python_src/px4_it/mavros/mission_test.py b/integrationtests/python_src/px4_it/mavros/mission_test.py deleted file mode 100755 index c4134cff00..0000000000 --- a/integrationtests/python_src/px4_it/mavros/mission_test.py +++ /dev/null @@ -1,358 +0,0 @@ -#!/usr/bin/env python3 -#*************************************************************************** -# -# Copyright (c) 2015-2016 PX4 Development Team. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 3. Neither the name PX4 nor the names of its contributors may be -# used to endorse or promote products derived from this software -# without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -#***************************************************************************/ - -# -# @author Andreas Antener -# - -PKG = 'px4' - -import rospy -import glob -import json -import math -import os -import numpy as np -from pyulog import ULog -import sys -from mavros import mavlink -from mavros_msgs.msg import Mavlink, Waypoint, WaypointReached -from mavros_test_common import MavrosTestCommon -from pymavlink import mavutil -from threading import Thread - - -def get_last_log(): - try: - log_path = os.environ['PX4_LOG_DIR'] - except KeyError: - try: - log_path = os.path.join(os.environ['ROS_HOME'], 'log') - except KeyError: - log_path = os.path.join(os.environ['HOME'], '.ros/log') - last_log_dir = sorted(glob.glob(os.path.join(log_path, '*')))[-1] - last_log = sorted(glob.glob(os.path.join(last_log_dir, '*.ulg')))[-1] - return last_log - - -def analyze_estimator_attitude(log_file): - """Compute attitude estimator error metrics from a ULog file.""" - ulog = ULog(log_file) - - att = ulog.get_dataset('vehicle_attitude').data - att_gt = ulog.get_dataset('vehicle_attitude_groundtruth').data - - def quat_to_euler(q0, q1, q2, q3): - """Quaternion (w,x,y,z) to (roll, pitch, yaw) via ZYX Tait-Bryan.""" - roll = np.arctan2(2 * (q0 * q1 + q2 * q3), 1 - 2 * (q1**2 + q2**2)) - sinp = 2 * (q0 * q2 - q3 * q1) - pitch = np.where(np.abs(sinp) >= 1, - np.copysign(np.pi / 2, sinp), np.arcsin(sinp)) - yaw = np.arctan2(2 * (q0 * q3 + q1 * q2), 1 - 2 * (q2**2 + q3**2)) - return roll, pitch, yaw - - roll, pitch, yaw = quat_to_euler( - att['q[0]'], att['q[1]'], att['q[2]'], att['q[3]']) - roll_gt, pitch_gt, yaw_gt = quat_to_euler( - att_gt['q[0]'], att_gt['q[1]'], att_gt['q[2]'], att_gt['q[3]']) - - # interpolate groundtruth onto attitude timestamps - ts = att['timestamp'] - ts_gt = att_gt['timestamp'] - roll_gt = np.interp(ts, ts_gt, roll_gt) - pitch_gt = np.interp(ts, ts_gt, pitch_gt) - yaw_gt = np.interp(ts, ts_gt, yaw_gt) - - wrap = lambda x: np.arcsin(np.sin(x)) - e_roll = wrap(roll - roll_gt) - e_pitch = wrap(pitch - pitch_gt) - e_yaw = wrap(yaw - yaw_gt) - - return { - 'roll_error_mean': np.rad2deg(np.mean(e_roll)), - 'pitch_error_mean': np.rad2deg(np.mean(e_pitch)), - 'yaw_error_mean': np.rad2deg(np.mean(e_yaw)), - 'roll_error_std': np.rad2deg(np.std(e_roll)), - 'pitch_error_std': np.rad2deg(np.std(e_pitch)), - 'yaw_error_std': np.rad2deg(np.std(e_yaw)), - } - - -def read_mission(mission_filename): - wps = [] - with open(mission_filename, 'r') as f: - for waypoint in read_plan_file(f): - wps.append(waypoint) - rospy.logdebug(waypoint) - - # set first item to current - if wps: - wps[0].is_current = True - - return wps - - -def read_plan_file(f): - d = json.load(f) - if 'mission' in d: - d = d['mission'] - - if 'items' in d: - for wp in d['items']: - yield Waypoint( - is_current=False, - frame=int(wp['frame']), - command=int(wp['command']), - param1=float('nan' - if wp['params'][0] is None else wp['params'][0]), - param2=float('nan' - if wp['params'][1] is None else wp['params'][1]), - param3=float('nan' - if wp['params'][2] is None else wp['params'][2]), - param4=float('nan' - if wp['params'][3] is None else wp['params'][3]), - x_lat=float(wp['params'][4]), - y_long=float(wp['params'][5]), - z_alt=float(wp['params'][6]), - autocontinue=bool(wp['autoContinue'])) - else: - raise IOError("no mission items") - - -class MavrosMissionTest(MavrosTestCommon): - """ - Run a mission - """ - - def setUp(self): - super(self.__class__, self).setUp() - - self.mission_item_reached = -1 # first mission item is 0 - self.mission_name = "" - - self.mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1) - self.mission_item_reached_sub = rospy.Subscriber( - 'mavros/mission/reached', WaypointReached, - self.mission_item_reached_callback) - - # need to simulate heartbeat to prevent datalink loss detection - self.hb_mav_msg = mavutil.mavlink.MAVLink_heartbeat_message( - mavutil.mavlink.MAV_TYPE_GCS, 0, 0, 0, 0, 0) - self.hb_mav_msg.pack(mavutil.mavlink.MAVLink('', 2, 1)) - self.hb_ros_msg = mavlink.convert_to_rosmsg(self.hb_mav_msg) - self.hb_thread = Thread(target=self.send_heartbeat, args=()) - self.hb_thread.daemon = True - self.hb_thread.start() - - def tearDown(self): - super(MavrosMissionTest, self).tearDown() - - # - # Helper methods - # - def send_heartbeat(self): - rate = rospy.Rate(2) # Hz - while not rospy.is_shutdown(): - self.mavlink_pub.publish(self.hb_ros_msg) - try: # prevent garbage in console output when thread is killed - rate.sleep() - except rospy.ROSInterruptException: - pass - - def mission_item_reached_callback(self, data): - if self.mission_item_reached != data.wp_seq: - rospy.loginfo("mission item reached: {0}".format(data.wp_seq)) - self.mission_item_reached = data.wp_seq - - def distance_to_wp(self, lat, lon, alt): - """alt(amsl): meters""" - R = 6371000 # metres - rlat1 = math.radians(lat) - rlat2 = math.radians(self.global_position.latitude) - - rlat_d = math.radians(self.global_position.latitude - lat) - rlon_d = math.radians(self.global_position.longitude - lon) - - a = (math.sin(rlat_d / 2) * math.sin(rlat_d / 2) + math.cos(rlat1) * - math.cos(rlat2) * math.sin(rlon_d / 2) * math.sin(rlon_d / 2)) - c = 2 * math.atan2(math.sqrt(a), math.sqrt(1 - a)) - - d = R * c - alt_d = abs(alt - self.altitude.amsl) - - rospy.logdebug("d: {0}, alt_d: {1}".format(d, alt_d)) - return d, alt_d - - def reach_position(self, lat, lon, alt, timeout, index): - """alt(amsl): meters, timeout(int): seconds""" - rospy.loginfo( - "trying to reach waypoint | lat: {0:.9f}, lon: {1:.9f}, alt: {2:.2f}, index: {3}". - format(lat, lon, alt, index)) - best_pos_xy_d = None - best_pos_z_d = None - reached = False - mission_length = len(self.mission_wp.waypoints) - - # does it reach the position in 'timeout' seconds? - loop_freq = 2 # Hz - rate = rospy.Rate(loop_freq) - for i in range(timeout * loop_freq): - pos_xy_d, pos_z_d = self.distance_to_wp(lat, lon, alt) - - # remember best distances - if not best_pos_xy_d or best_pos_xy_d > pos_xy_d: - best_pos_xy_d = pos_xy_d - if not best_pos_z_d or best_pos_z_d > pos_z_d: - best_pos_z_d = pos_z_d - - # FCU advanced to the next mission item, or finished mission - reached = ( - # advanced to next wp - (index < self.mission_wp.current_seq) - # end of mission - or (index == (mission_length - 1) and - self.mission_item_reached == index)) - - if reached: - rospy.loginfo( - "position reached | pos_xy_d: {0:.2f}, pos_z_d: {1:.2f}, index: {2} | seconds: {3} of {4}". - format(pos_xy_d, pos_z_d, index, i / loop_freq, timeout)) - break - elif i == 0 or ((i / loop_freq) % 10) == 0: - # log distance first iteration and every 10 sec - rospy.loginfo( - "current distance to waypoint | pos_xy_d: {0:.2f}, pos_z_d: {1:.2f}, index: {2}". - format(pos_xy_d, pos_z_d, index)) - - try: - rate.sleep() - except rospy.ROSException as e: - self.fail(e) - - self.assertTrue( - reached, - "position not reached | lat: {0:.9f}, lon: {1:.9f}, alt: {2:.2f}, current pos_xy_d: {3:.2f}, current pos_z_d: {4:.2f}, best pos_xy_d: {5:.2f}, best pos_z_d: {6:.2f}, index: {7} | timeout(seconds): {8}". - format(lat, lon, alt, pos_xy_d, pos_z_d, best_pos_xy_d, - best_pos_z_d, index, timeout)) - - # - # Test method - # - def test_mission(self): - """Test mission""" - if len(sys.argv) < 2: - self.fail("usage: mission_test.py mission_file") - return - - self.mission_name = sys.argv[1] - mission_file = os.path.dirname( - os.path.realpath(__file__)) + "/missions/" + sys.argv[1] - - rospy.loginfo("reading mission {0}".format(mission_file)) - try: - wps = read_mission(mission_file) - except IOError as e: - self.fail(e) - - # make sure the simulation is ready to start the mission - self.wait_for_topics(60) - self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, - 10, -1) - self.wait_for_mav_type(10) - - # push waypoints to FCU and start mission - self.send_wps(wps, 30) - self.log_topic_vars() - self.set_mode("AUTO.MISSION", 5) - self.set_arm(True, 5) - - rospy.loginfo("run mission {0}".format(self.mission_name)) - for index, waypoint in enumerate(wps): - # only check position for waypoints where this makes sense - if (waypoint.frame == Waypoint.FRAME_GLOBAL_REL_ALT or - waypoint.frame == Waypoint.FRAME_GLOBAL): - alt = waypoint.z_alt - if waypoint.frame == Waypoint.FRAME_GLOBAL_REL_ALT: - alt += self.altitude.amsl - self.altitude.relative - - self.reach_position(waypoint.x_lat, waypoint.y_long, alt, 60, - index) - - # check if VTOL transition happens if applicable - if (waypoint.command == mavutil.mavlink.MAV_CMD_NAV_VTOL_TAKEOFF or - waypoint.command == mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND - or waypoint.command == - mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION): - transition = waypoint.param1 # used by MAV_CMD_DO_VTOL_TRANSITION - if waypoint.command == mavutil.mavlink.MAV_CMD_NAV_VTOL_TAKEOFF: # VTOL takeoff implies transition to FW - transition = mavutil.mavlink.MAV_VTOL_STATE_FW - if waypoint.command == mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND: # VTOL land implies transition to MC - transition = mavutil.mavlink.MAV_VTOL_STATE_MC - - self.wait_for_vtol_state(transition, 60, index) - - # after reaching position, wait for landing detection if applicable - if (waypoint.command == mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND or - waypoint.command == mavutil.mavlink.MAV_CMD_NAV_LAND): - self.wait_for_landed_state( - mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, 120, index) - - self.set_arm(False, 5) - self.clear_wps(5) - - rospy.loginfo("mission done, calculating performance metrics") - last_log = get_last_log() - rospy.loginfo("log file {0}".format(last_log)) - res = analyze_estimator_attitude(last_log) - - # enforce performance - self.assertTrue(abs(res['roll_error_mean']) < 5.0, str(res)) - self.assertTrue(abs(res['pitch_error_mean']) < 5.0, str(res)) - self.assertTrue(abs(res['yaw_error_mean']) < 5.0, str(res)) - - self.assertTrue(res['roll_error_std'] < 5.0, str(res)) - self.assertTrue(res['pitch_error_std'] < 5.0, str(res)) - - # TODO: fix by excluding initial heading init and reset preflight - self.assertTrue(res['yaw_error_std'] < 15.0, str(res)) - - -if __name__ == '__main__': - import rostest - rospy.init_node('test_node', anonymous=True) - - name = "mavros_mission_test" - if len(sys.argv) > 1: - name += "-%s" % sys.argv[1] - rostest.rosrun(PKG, name, MavrosMissionTest) diff --git a/integrationtests/python_src/px4_it/mavros/missions/FW_mission_1.plan b/integrationtests/python_src/px4_it/mavros/missions/FW_mission_1.plan deleted file mode 100644 index 03986f692e..0000000000 --- a/integrationtests/python_src/px4_it/mavros/missions/FW_mission_1.plan +++ /dev/null @@ -1,123 +0,0 @@ -{ - "fileType": "Plan", - "geoFence": { - "circles": [ - ], - "polygons": [ - ], - "version": 2 - }, - "groundStation": "QGroundControl", - "mission": { - "cruiseSpeed": 15, - "firmwareType": 12, - "hoverSpeed": 5, - "items": [ - { - "AMSLAltAboveTerrain": 50, - "Altitude": 50, - "AltitudeMode": 0, - "autoContinue": true, - "command": 22, - "doJumpId": 1, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.397757116360204, - 8.54802567938998, - 50 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": 50, - "Altitude": 50, - "AltitudeMode": 0, - "autoContinue": true, - "command": 16, - "doJumpId": 2, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.395834920202326, - 8.548141558196932, - 50 - ], - "type": "SimpleItem" - }, - { - "autoContinue": true, - "command": 189, - "doJumpId": 3, - "frame": 2, - "params": [ - 0, - 0, - 0, - 0, - 0, - 0, - 0 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": 25, - "Altitude": 25, - "AltitudeMode": 0, - "autoContinue": true, - "command": 31, - "doJumpId": 4, - "frame": 3, - "params": [ - 1, - 50, - 0, - 1, - 47.39580995751514, - 8.545613891100459, - 25 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": 0, - "Altitude": 0, - "AltitudeMode": 0, - "autoContinue": true, - "command": 21, - "doJumpId": 5, - "frame": 3, - "params": [ - 25, - 0, - 0, - null, - 47.39757125904106, - 8.545589014690734, - 0 - ], - "type": "SimpleItem" - } - ], - "plannedHomePosition": [ - 47.397742, - 8.545594, - 489 - ], - "vehicleType": 1, - "version": 2 - }, - "rallyPoints": { - "points": [ - ], - "version": 2 - }, - "version": 1 -} diff --git a/integrationtests/python_src/px4_it/mavros/missions/MC_mission_box.plan b/integrationtests/python_src/px4_it/mavros/missions/MC_mission_box.plan deleted file mode 100644 index f1b04ffd63..0000000000 --- a/integrationtests/python_src/px4_it/mavros/missions/MC_mission_box.plan +++ /dev/null @@ -1,145 +0,0 @@ -{ - "fileType": "Plan", - "geoFence": { - "circles": [ - ], - "polygons": [ - ], - "version": 2 - }, - "groundStation": "QGroundControl", - "mission": { - "cruiseSpeed": 15, - "firmwareType": 12, - "hoverSpeed": 5, - "items": [ - { - "AMSLAltAboveTerrain": null, - "Altitude": 5, - "AltitudeMode": 0, - "autoContinue": true, - "command": 22, - "doJumpId": 1, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.39773941040039, - 8.5455904006958, - 5 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": null, - "Altitude": 10, - "AltitudeMode": 0, - "autoContinue": true, - "command": 16, - "doJumpId": 2, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.39787292480469, - 8.54559326171875, - 10 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": null, - "Altitude": 10, - "AltitudeMode": 0, - "autoContinue": true, - "command": 16, - "doJumpId": 3, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.39787292480469, - 8.545341491699219, - 10 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": null, - "Altitude": 10, - "AltitudeMode": 0, - "autoContinue": true, - "command": 16, - "doJumpId": 4, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.39773941040039, - 8.545336723327637, - 10 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": null, - "Altitude": 10, - "AltitudeMode": 0, - "autoContinue": true, - "command": 16, - "doJumpId": 5, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.39773941040039, - 8.5455904006958, - 10 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": null, - "Altitude": 0, - "AltitudeMode": 0, - "autoContinue": true, - "command": 21, - "doJumpId": 6, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.39773941040039, - 8.545591354370117, - 0 - ], - "type": "SimpleItem" - } - ], - "plannedHomePosition": [ - 47.397742, - 8.545594, - 488 - ], - "vehicleType": 2, - "version": 2 - }, - "rallyPoints": { - "points": [ - ], - "version": 2 - }, - "version": 1 -} diff --git a/integrationtests/python_src/px4_it/mavros/missions/MC_safe_landing.plan b/integrationtests/python_src/px4_it/mavros/missions/MC_safe_landing.plan deleted file mode 100644 index f2593118ba..0000000000 --- a/integrationtests/python_src/px4_it/mavros/missions/MC_safe_landing.plan +++ /dev/null @@ -1,107 +0,0 @@ -{ - "fileType": "Plan", - "geoFence": { - "circles": [ - ], - "polygons": [ - ], - "version": 2 - }, - "groundStation": "QGroundControl", - "mission": { - "cruiseSpeed": 15, - "firmwareType": 12, - "hoverSpeed": 5, - "items": [ - { - "AMSLAltAboveTerrain": null, - "Altitude": 18, - "AltitudeMode": 1, - "autoContinue": true, - "command": 22, - "doJumpId": 1, - "frame": 3, - "params": [ - 15, - 0, - 0, - null, - 47.3977394, - 8.5455942, - 18 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": null, - "Altitude": 18, - "AltitudeMode": 1, - "autoContinue": true, - "command": 16, - "doJumpId": 2, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.3977394, - 8.5456982, - 18 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": null, - "Altitude": 18, - "AltitudeMode": 1, - "autoContinue": true, - "command": 16, - "doJumpId": 3, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.3977432, - 8.545805, - 18 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": null, - "Altitude": 0, - "AltitudeMode": 1, - "autoContinue": true, - "command": 21, - "doJumpId": 4, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.3977432, - 8.545804, - 0 - ], - "type": "SimpleItem" - } - ], - "plannedHomePosition": [ - 47.3977419, - 8.5455941, - 489 - ], - "vehicleType": 2, - "version": 2 - }, - "rallyPoints": { - "points": [ - ], - "version": 2 - }, - "version": 1 -} diff --git a/integrationtests/python_src/px4_it/mavros/missions/VTOL_mission_1.plan b/integrationtests/python_src/px4_it/mavros/missions/VTOL_mission_1.plan deleted file mode 100644 index 8068b43127..0000000000 --- a/integrationtests/python_src/px4_it/mavros/missions/VTOL_mission_1.plan +++ /dev/null @@ -1,107 +0,0 @@ -{ - "fileType": "Plan", - "geoFence": { - "circles": [ - ], - "polygons": [ - ], - "version": 2 - }, - "groundStation": "QGroundControl", - "mission": { - "cruiseSpeed": 15, - "firmwareType": 12, - "hoverSpeed": 5, - "items": [ - { - "AMSLAltAboveTerrain": 15, - "Altitude": 15, - "AltitudeMode": 0, - "autoContinue": true, - "command": 84, - "doJumpId": 1, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.39773615102264, - 8.547064163497595, - 15 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": null, - "Altitude": 30, - "AltitudeMode": 0, - "autoContinue": true, - "command": 31, - "doJumpId": 2, - "frame": 3, - "params": [ - 0, - 50, - 0, - 1, - 47.396840504834636, - 8.548309212214804, - 30 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": null, - "Altitude": 15, - "AltitudeMode": 0, - "autoContinue": true, - "command": 16, - "doJumpId": 3, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.39617583578575, - 8.546774195044463, - 15 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": 0, - "Altitude": 0, - "AltitudeMode": 0, - "autoContinue": true, - "command": 85, - "doJumpId": 4, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.39706525003061, - 8.545322355693173, - 0 - ], - "type": "SimpleItem" - } - ], - "plannedHomePosition": [ - 47.397742, - 8.545594, - 489 - ], - "vehicleType": 20, - "version": 2 - }, - "rallyPoints": { - "points": [ - ], - "version": 2 - }, - "version": 1 -} diff --git a/launch/mavros_posix_sitl.launch b/launch/mavros_posix_sitl.launch deleted file mode 100644 index 31b93fa15d..0000000000 --- a/launch/mavros_posix_sitl.launch +++ /dev/null @@ -1,54 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/pub_test.launch b/launch/pub_test.launch deleted file mode 100644 index 769a51aa9c..0000000000 --- a/launch/pub_test.launch +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/platforms/posix/CMakeLists.txt b/platforms/posix/CMakeLists.txt index 28fe07268b..9bf1564d3d 100644 --- a/platforms/posix/CMakeLists.txt +++ b/platforms/posix/CMakeLists.txt @@ -212,7 +212,6 @@ elseif("${PX4_BOARD}" MATCHES "sitl") # px4 dirs install( DIRECTORY - ${PROJECT_SOURCE_DIR}/integrationtests ${PROJECT_SOURCE_DIR}/launch ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} DESTINATION diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 398cdae7b4..cc1409286f 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -273,6 +273,8 @@ #define DRV_TEMP_DEVTYPE_TMP102 0xF0 #define DRV_ADC_DEVTYPE_ADS7128 0xF1 +#define DRV_MOTOR_DEVTYPE_HIWONDER_EMM 0xED + #define DRV_DEVTYPE_UNUSED 0xff #endif /* _DRV_SENSOR_H */ diff --git a/src/drivers/hiwonder_emm/CMakeLists.txt b/src/drivers/hiwonder_emm/CMakeLists.txt new file mode 100644 index 0000000000..198de763af --- /dev/null +++ b/src/drivers/hiwonder_emm/CMakeLists.txt @@ -0,0 +1,44 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +px4_add_module( + MODULE drivers__hiwonder_emm + MAIN hiwonder_emm + COMPILE_FLAGS + SRCS + HiwonderEMM.cpp + HiwonderEMM.hpp + MODULE_CONFIG + module.yaml + DEPENDS + mixer_module + ) diff --git a/src/drivers/hiwonder_emm/HiwonderEMM.cpp b/src/drivers/hiwonder_emm/HiwonderEMM.cpp new file mode 100644 index 0000000000..a6badb9447 --- /dev/null +++ b/src/drivers/hiwonder_emm/HiwonderEMM.cpp @@ -0,0 +1,255 @@ +/**************************************************************************** + * + * Copyright (c) 2026 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "HiwonderEMM.hpp" + +ModuleBase::Descriptor HiwonderEMM::desc{ + HiwonderEMM::task_spawn, + HiwonderEMM::custom_command, + HiwonderEMM::print_usage, +}; + +HiwonderEMM::HiwonderEMM() : + OutputModuleInterface(MODULE_NAME, px4::wq_configurations::hp_default), I2C(DRV_MOTOR_DEVTYPE_HIWONDER_EMM, + MODULE_NAME, I2CBUS, I2C_ADDR, 400000) +{ + _mixing_output.setAllMinValues(0); + _mixing_output.setAllMaxValues(255); +} + +int HiwonderEMM::init() +{ + int ret = I2C::init(); + + if (ret != PX4_OK) { + PX4_ERR("I2C init failed. Error: %d", ret); + return ret; + } + + const uint8_t set_motor_type[2] = {MOTOR_TYPE_ADDR, MOTOR_TYPE_JGB37_520_12V_110RPM}; + ret = transfer(set_motor_type, sizeof(set_motor_type), nullptr, 0); + + if (ret != PX4_OK) { + PX4_ERR("Failed to set motor type. Error: %d", ret); + return ret; + } + + const uint8_t set_motor_polarity[2] = {MOTOR_ENCODER_POLARITY_ADDR, 0}; + ret = transfer(set_motor_polarity, sizeof(set_motor_polarity), nullptr, 0); + + if (ret != PX4_OK) { + PX4_ERR("Failed to set encoder polarity. Error: %d", ret); + return ret; + } + + this->ChangeWorkQueue(px4::device_bus_to_wq(this->get_device_id())); + + PX4_INFO("Hiwonder EMM running on I2C bus %d address 0x%.2x", this->get_device_bus(), this->get_device_address()); + + ScheduleNow(); + + return PX4_OK; +} + +bool HiwonderEMM::updateOutputs(float outputs[MAX_ACTUATORS], unsigned num_outputs, + unsigned num_control_groups_updated) +{ + int8_t speed_values[CHANNEL_COUNT]; + + for (unsigned i = 0; i < num_outputs && i < CHANNEL_COUNT; i++) { + speed_values[i] = static_cast(outputs[i] - 128.0f); + } + + set_motor_speed(speed_values, CHANNEL_COUNT); + + return true; +} + +void HiwonderEMM::Run() +{ + if (should_exit()) { + ScheduleClear(); + _mixing_output.unregister(); + exit_and_cleanup(desc); + return; + } + + _mixing_output.update(); + + if (_parameter_update_sub.updated()) { + parameter_update_s pu; + _parameter_update_sub.copy(&pu); + updateParams(); + } + + _mixing_output.updateSubscriptions(false); +} + +int HiwonderEMM::probe() +{ + int ret = I2C::probe(); + + if (ret != PX4_OK) { + PX4_ERR("I2C probe failed. Error: %d", ret); + return ret; + } + + int adc_value{0}; + ret = read_adc(adc_value); + + if (ret != PX4_OK) { + PX4_ERR("Failed to probe Hiwonder EMM. Error: %d", ret); + return ret; + } + + PX4_INFO("Hiwonder EMM found"); + + return PX4_OK; +} + +int HiwonderEMM::read_adc(int &adc_value) +{ + const uint8_t cmd = ADC_BAT_ADDR; + uint8_t buf[2] = {}; + const int ret = transfer(&cmd, sizeof(cmd), buf, sizeof(buf)); + + if (ret != PX4_OK) { + PX4_ERR("Failed to read ADC. Error: %d", ret); + adc_value = 0; + return ret; + } + + adc_value = buf[0] | (buf[1] << 8); + return ret; +} + +int HiwonderEMM::read_encoder_counts(int32_t *encoder_counts, const uint8_t count) +{ + const uint8_t cmd = MOTOR_ENCODER_TOTAL_ADDR; + uint8_t buf[CHANNEL_COUNT * 4]; // Each encoder count is a 32-bit integer (4 bytes) + const int ret = transfer(&cmd, sizeof(cmd), buf, sizeof(buf)); + + if (ret != PX4_OK) { + PX4_ERR("Failed to read encoder counts. Error: %d", ret); + return ret; + } + + for (unsigned i = 0; i < count && i < CHANNEL_COUNT; i++) { + encoder_counts[i] = buf[i * 4] | (buf[i * 4 + 1] << 8) | (buf[i * 4 + 2] << 16) | (buf[i * 4 + 3] << 24); + } + + return ret; +} + +int HiwonderEMM::set_motor_speed(const int8_t *speed_values, const uint8_t count) +{ + uint8_t cmd[1 + CHANNEL_COUNT] {}; + cmd[0] = MOTOR_FIXED_SPEED_ADDR; + + for (unsigned int i = 0; i < count && i < CHANNEL_COUNT; i++) { + cmd[i + 1] = speed_values[i]; + } + + const int ret = transfer(cmd, sizeof(cmd), nullptr, 0); + + if (ret != PX4_OK) { + if (!_set_speed_failed) { + PX4_ERR("Failed to set motor speed. Error: %d", ret); + _set_speed_failed = true; + } + + } else if (_set_speed_failed) { + PX4_INFO("Motor speed write recovered"); + _set_speed_failed = false; + } + + return ret; +} + +int HiwonderEMM::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +Hiwonder encoder motor module driver for PX4. +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("hiwonder_emm", "driver"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the task"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +int HiwonderEMM::print_status() { + int ret = ModuleBase::print_status(); + PX4_INFO("HiwonderEMM @I2C Bus %d, address 0x%.2x", + this->get_device_bus(), + this->get_device_address()); + + return ret; +} + +int HiwonderEMM::custom_command(int argc, char **argv) { + return PX4_OK; +} + +int HiwonderEMM::task_spawn(int argc, char **argv) { + auto *instance = new HiwonderEMM(); + + if (instance) { + desc.object.store(instance); + desc.task_id = task_id_is_work_queue; + + if (instance->init() == PX4_OK) { + return PX4_OK; + } + + } else { + PX4_ERR("alloc failed"); + } + + delete instance; + desc.object.store(nullptr); + desc.task_id = -1; + + return PX4_ERROR; +} + +extern "C" __EXPORT int hiwonder_emm_main(int argc, char *argv[]){ + return ModuleBase::main(HiwonderEMM::desc, argc, argv); +} diff --git a/src/drivers/hiwonder_emm/HiwonderEMM.hpp b/src/drivers/hiwonder_emm/HiwonderEMM.hpp new file mode 100644 index 0000000000..0d94656680 --- /dev/null +++ b/src/drivers/hiwonder_emm/HiwonderEMM.hpp @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (c) 2026 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file HiwonderEMM.hpp + * + * Driver for the Hiwonder 4-channel encoder motor driver over I2C. + * + * Product: https://www.hiwonder.com/products/4-channel-encoder-motor-driver + * + */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +static constexpr uint8_t I2C_ADDR = 0x34; // I2C address +static constexpr uint8_t ADC_BAT_ADDR = 0; // Voltage address +static constexpr uint8_t MOTOR_TYPE_ADDR = 0x14; // Set the motor type +static constexpr uint8_t MOTOR_ENCODER_POLARITY_ADDR = 21; // Set the encoder direction polarity +static constexpr uint8_t MOTOR_FIXED_PWM_ADDR = 31; // Fixed PWM control, open loop +static constexpr uint8_t MOTOR_FIXED_SPEED_ADDR = 51; // Fixed speed control, closed loop +static constexpr uint8_t MOTOR_ENCODER_TOTAL_ADDR = 60; // Total pulse value of 4 encoder motors +static constexpr uint8_t MOTOR_TYPE_WITHOUT_ENCODER = 0; // Motor without encoder +static constexpr uint8_t MOTOR_TYPE_TT = 1; // TT encoder motor +static constexpr uint8_t MOTOR_TYPE_N20 = 2; // N20 encoder motor +static constexpr uint8_t MOTOR_TYPE_JGB37_520_12V_110RPM = 3; // JGB37 encoder motor +static constexpr uint8_t I2CBUS = 1; // I2C bus number +static constexpr uint8_t CHANNEL_COUNT = 4; // Number of output channels + +class HiwonderEMM : public ModuleBase, public OutputModuleInterface, public device::I2C +{ +public: + static Descriptor desc; + + HiwonderEMM(); + ~HiwonderEMM() override = default; + + // I2C + int init() override; + + // ModuleBase + static int task_spawn(int argc, char *argv[]); + static int custom_command(int argc, char *argv[]); + static int print_usage(const char *reason = nullptr); + int print_status() override; + + // OutputModuleInterface + bool updateOutputs(float outputs[MAX_ACTUATORS], unsigned num_outputs, + unsigned num_control_groups_updated) override; + +protected: + int probe() override; + +private: + MixingOutput _mixing_output { + "EMM", + CHANNEL_COUNT, + *this, + MixingOutput::SchedulingPolicy::Auto, + false + }; + uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + void Run() override; + + /** + * @brief Read the input voltage supplied to the motor driver. + * @param adc_value [mV] Reference to store the ADC value. + * @return OK if the transfer was successful, -errno otherwise. + */ + int read_adc(int &adc_value); + + /** + * @brief Read the encoder counts for all motors. + * @param encoder_counts Array to store the encoder counts for each motor. + * @param count Number of encoder counts to read (should be equal to CHANNEL_COUNT). + * @return OK if the transfer was successful, -errno otherwise. + */ + int read_encoder_counts(int32_t *encoder_counts, const uint8_t count); + + /** + * @brief Set the speed values for the motors. + * @param speed_values Array of speed values for each motor in the range [0, 255]. + * 128 represents stop, values below 128 represent reverse motion, + * and values above 128 represent forward motion. + * @param count Number of speed values provided in the array (should be equal to CHANNEL_COUNT). + * @return OK if the transfer was successful, -errno otherwise. + */ + int set_motor_speed(const int8_t *speed_values, const uint8_t count); + + bool _set_speed_failed{false}; +}; diff --git a/src/drivers/hiwonder_emm/Kconfig b/src/drivers/hiwonder_emm/Kconfig new file mode 100644 index 0000000000..eda4a7f8f5 --- /dev/null +++ b/src/drivers/hiwonder_emm/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_HIWONDER_EMM + bool "hiwonder_emm" + default n + ---help--- + Enable support for hiwonder encoder motor module diff --git a/src/drivers/hiwonder_emm/module.yaml b/src/drivers/hiwonder_emm/module.yaml new file mode 100644 index 0000000000..b0018720ca --- /dev/null +++ b/src/drivers/hiwonder_emm/module.yaml @@ -0,0 +1,22 @@ +module_name: Hiwonder EMM Driver + +actuator_output: + output_groups: + - param_prefix: EMM + channel_label: 'Channel' + standard_params: + disarmed: { min: 0, max: 255, default: 128 } + failsafe: { min: 0, max: 255} + num_channels: 4 + +parameters: + - group: Hiwonder EMM + definitions: + HIWONDER_EMM_EN: + description: + short: Enable the Hiwonder Encoder Motor Module (EMM) motor driver. + long: | + Enable the Hiwonder Encoder Motor Module (EMM) motor driver. + type: boolean + default: 0 + reboot_required: true diff --git a/src/drivers/uavcan/uavcan_drivers/posix/include/uavcan_posix/dynamic_node_id_server/file_event_tracer.hpp b/src/drivers/uavcan/uavcan_drivers/posix/include/uavcan_posix/dynamic_node_id_server/file_event_tracer.hpp index fe6129318d..7deb9a1339 100644 --- a/src/drivers/uavcan/uavcan_drivers/posix/include/uavcan_posix/dynamic_node_id_server/file_event_tracer.hpp +++ b/src/drivers/uavcan/uavcan_drivers/posix/include/uavcan_posix/dynamic_node_id_server/file_event_tracer.hpp @@ -37,10 +37,13 @@ class FileEventTracer : public uavcan::dynamic_node_id_server::IEventTracer typedef uavcan::MakeString::Type PathString; PathString path_; + bool initialized_ = false; protected: virtual void onEvent(uavcan::dynamic_node_id_server::TraceCode code, uavcan::int64_t argument) { + if (!initialized_) { return; } + using namespace std; timespec ts = timespec(); // If clock_gettime() fails, zero time will be used @@ -89,6 +92,8 @@ public: if (fd >= 0) { (void)close(fd); } + + initialized_ = true; } return rv; diff --git a/src/drivers/uavcan/uavcan_params.yaml b/src/drivers/uavcan/uavcan_params.yaml index 97cac23a22..09e73ccfd7 100644 --- a/src/drivers/uavcan/uavcan_params.yaml +++ b/src/drivers/uavcan/uavcan_params.yaml @@ -30,6 +30,13 @@ parameters: min: 1 max: 125 reboot_required: true + UAVCAN_TRACE_EN: + description: + short: UAVCAN event tracing + long: Enable logging of UAVCAN events + type: boolean + default: 1 + reboot_required: true UAVCAN_BITRATE: description: short: UAVCAN CAN bus bitrate diff --git a/src/drivers/uavcan/uavcan_servers.cpp b/src/drivers/uavcan/uavcan_servers.cpp index 1c35483df4..f808c01e73 100644 --- a/src/drivers/uavcan/uavcan_servers.cpp +++ b/src/drivers/uavcan/uavcan_servers.cpp @@ -104,11 +104,16 @@ int UavcanServers::init() } /* Initialize trace in the UAVCAN_NODE_DB_PATH directory */ - ret = _tracer.init(UAVCAN_LOG_FILE); + int32_t trace_en = 1; + (void)param_get(param_find("UAVCAN_TRACE_EN"), &trace_en); - if (ret < 0) { - PX4_ERR("FileEventTracer init: %d, errno: %d", ret, errno); - return ret; + if (trace_en) { + ret = _tracer.init(UAVCAN_LOG_FILE); + + if (ret < 0) { + PX4_ERR("FileEventTracer init: %d, errno: %d", ret, errno); + return ret; + } } /* hardware version */ diff --git a/src/lib/parameters/px4params/markdownout.py b/src/lib/parameters/px4params/markdownout.py index 77501cf099..91c1f8893f 100644 --- a/src/lib/parameters/px4params/markdownout.py +++ b/src/lib/parameters/px4params/markdownout.py @@ -85,10 +85,19 @@ If a listed parameter is missing from the Firmware see: [Finding/Updating Parame bitmask_output+=f"- `{bit}`: {bit_text}\n" bitmask_output+='\n\n' - if is_boolean and def_val=='1': - def_val='Enabled (1)' - if is_boolean and def_val=='0': - def_val='Disabled (0)' + if is_boolean: + BOOLEAN_LABELS = { + '0': 'Disabled', + '1': 'Enabled' + } + # Give def_value an explanatory string (is def_value if no match) + def_val = f"{BOOLEAN_LABELS[def_val]} ({def_val})" if def_val in BOOLEAN_LABELS else def_val + + # Format values and their descriptions for display. + boolean_values = '**Values:**\n\n' + for key, label in BOOLEAN_LABELS.items(): + boolean_values += f"- `{key}`: {label}\n" + boolean_values += '\n' result += f'### {name} (`{type}`)' + ' {#' + name + '}\n\n' if apply_note_board_specific_group: @@ -99,6 +108,8 @@ If a listed parameter is missing from the Firmware see: [Finding/Updating Parame result += f'{short_desc}\n\n' if long_desc: result += f'{long_desc}\n\n' + if is_boolean: + result += boolean_values if enum_codes: result += enum_output if bitmask_list: diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 3a42bc274f..22c80cd599 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1001,19 +1001,21 @@ void EKF2::initFusionControl() const int32_t sens_en = _param_ekf2_sens_en.get(); - _fc.gps.enabled = sens_en & (1 << SENS_EN_GPS0); - _fc.of.enabled = sens_en & (1 << SENS_EN_OF); - _fc.ev.enabled = sens_en & (1 << SENS_EN_EV); + _fc.gps.enabled = sens_en & SensEn::GPS0; + _fc.of.enabled = sens_en & SensEn::OF; + _fc.ev.enabled = sens_en & SensEn::EV; + + static constexpr SensEn kAgpBits[MAX_AGP_INSTANCES] = {SensEn::AGP0, SensEn::AGP1, SensEn::AGP2, SensEn::AGP3}; for (uint8_t i = 0; i < MAX_AGP_INSTANCES; i++) { - _fc.agp[i].enabled = sens_en & (1 << (SENS_EN_AGP0 + i)); + _fc.agp[i].enabled = sens_en & kAgpBits[i]; } - _fc.baro.enabled = sens_en & (1 << SENS_EN_BARO); - _fc.rng.enabled = sens_en & (1 << SENS_EN_RNG); - _fc.mag.enabled = sens_en & (1 << SENS_EN_MAG); - _fc.aspd.enabled = sens_en & (1 << SENS_EN_ASPD); - _fc.rngbcn.enabled = sens_en & (1 << SENS_EN_RNGBCN); + _fc.baro.enabled = sens_en & SensEn::BARO; + _fc.rng.enabled = sens_en & SensEn::RNG; + _fc.mag.enabled = sens_en & SensEn::MAG; + _fc.aspd.enabled = sens_en & SensEn::ASPD; + _fc.rngbcn.enabled = sens_en & SensEn::RNGBCN; } } @@ -1069,25 +1071,27 @@ void EKF2::syncSensEnParam() { int32_t sens_en = 0; - if (_fc.gps.enabled) { sens_en |= (1 << SENS_EN_GPS0); } + if (_fc.gps.enabled) { sens_en |= SensEn::GPS0; } - if (_fc.of.enabled) { sens_en |= (1 << SENS_EN_OF); } + if (_fc.of.enabled) { sens_en |= SensEn::OF; } - if (_fc.ev.enabled) { sens_en |= (1 << SENS_EN_EV); } + if (_fc.ev.enabled) { sens_en |= SensEn::EV; } + + static constexpr SensEn kAgpBits[MAX_AGP_INSTANCES] = {SensEn::AGP0, SensEn::AGP1, SensEn::AGP2, SensEn::AGP3}; for (uint8_t i = 0; i < MAX_AGP_INSTANCES; i++) { - if (_fc.agp[i].enabled) { sens_en |= (1 << (SENS_EN_AGP0 + i)); } + if (_fc.agp[i].enabled) { sens_en |= kAgpBits[i]; } } - if (_fc.baro.enabled) { sens_en |= (1 << SENS_EN_BARO); } + if (_fc.baro.enabled) { sens_en |= SensEn::BARO; } - if (_fc.rng.enabled) { sens_en |= (1 << SENS_EN_RNG); } + if (_fc.rng.enabled) { sens_en |= SensEn::RNG; } - if (_fc.mag.enabled) { sens_en |= (1 << SENS_EN_MAG); } + if (_fc.mag.enabled) { sens_en |= SensEn::MAG; } - if (_fc.aspd.enabled) { sens_en |= (1 << SENS_EN_ASPD); } + if (_fc.aspd.enabled) { sens_en |= SensEn::ASPD; } - if (_fc.rngbcn.enabled) { sens_en |= (1 << SENS_EN_RNGBCN); } + if (_fc.rngbcn.enabled) { sens_en |= SensEn::RNGBCN; } _param_ekf2_sens_en.set(sens_en); _param_ekf2_sens_en.commit_no_notification(); diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 9d52d47d17..07c6ccfa0a 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -407,18 +407,20 @@ private: uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)}; uORB::Publication _vehicle_command_ack_pub{ORB_ID(vehicle_command_ack)}; - enum SensEnBit : uint16_t { - SENS_EN_GPS0 = 0, - SENS_EN_GPS1 = 1, - SENS_EN_OF = 2, - SENS_EN_EV = 3, - SENS_EN_AGP0 = 4, - // bit: 5-7 reserved for AGP1..3 - SENS_EN_BARO = 8, - SENS_EN_RNG = 9, - SENS_EN_MAG = 10, - SENS_EN_ASPD = 11, - SENS_EN_RNGBCN = 12, + enum SensEn : uint16_t { + GPS0 = 1 << 0, + GPS1 = 1 << 1, + OF = 1 << 2, + EV = 1 << 3, + AGP0 = 1 << 4, + AGP1 = 1 << 5, + AGP2 = 1 << 6, + AGP3 = 1 << 7, + BARO = 1 << 8, + RNG = 1 << 9, + MAG = 1 << 10, + ASPD = 1 << 11, + RNGBCN = 1 << 12, }; bool _prev_armed{false}; diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index e3044c1ee7..fae125ecc5 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -190,6 +190,7 @@ void LoggedTopics::add_default_topics() add_optional_topic("estimator_selector_status", 10); add_optional_topic_multi("estimator_event_flags", 10); add_optional_topic_multi("estimator_optical_flow_vel", 200); + add_optional_topic_multi("estimator_fusion_control", 1000); add_optional_topic_multi("estimator_sensor_bias", 1000); add_optional_topic_multi("estimator_status", 200); add_optional_topic_multi("estimator_status_flags", 10); diff --git a/test/mavros_posix_test_mission.test b/test/mavros_posix_test_mission.test deleted file mode 100644 index 4d946f1b43..0000000000 --- a/test/mavros_posix_test_mission.test +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/test/mavros_posix_test_safe_landing.test b/test/mavros_posix_test_safe_landing.test deleted file mode 100644 index 909a5f86d2..0000000000 --- a/test/mavros_posix_test_safe_landing.test +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/test/mavros_posix_tests_iris_opt_flow.test b/test/mavros_posix_tests_iris_opt_flow.test deleted file mode 100644 index c7d3f71b14..0000000000 --- a/test/mavros_posix_tests_iris_opt_flow.test +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/test/mavros_posix_tests_missions.test b/test/mavros_posix_tests_missions.test deleted file mode 100644 index 16b6d62557..0000000000 --- a/test/mavros_posix_tests_missions.test +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/test/mavros_posix_tests_offboard_attctl.test b/test/mavros_posix_tests_offboard_attctl.test deleted file mode 100644 index 58fc2df6f0..0000000000 --- a/test/mavros_posix_tests_offboard_attctl.test +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/test/mavros_posix_tests_offboard_posctl.test b/test/mavros_posix_tests_offboard_posctl.test deleted file mode 100644 index 7fbb35737e..0000000000 --- a/test/mavros_posix_tests_offboard_posctl.test +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/test/mavros_posix_tests_offboard_rpyrt_ctl.test b/test/mavros_posix_tests_offboard_rpyrt_ctl.test deleted file mode 100644 index 6d26412d26..0000000000 --- a/test/mavros_posix_tests_offboard_rpyrt_ctl.test +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/test/mavsdk_tests/integration_test_runner/test_runner.py b/test/mavsdk_tests/integration_test_runner/test_runner.py index a29c5b90c2..ce3e396254 100644 --- a/test/mavsdk_tests/integration_test_runner/test_runner.py +++ b/test/mavsdk_tests/integration_test_runner/test_runner.py @@ -5,7 +5,7 @@ import os import re import sys import time -from typing import Any, Dict, List, NoReturn, TextIO, Optional +from typing import Any, Callable, Dict, List, NoReturn, TextIO, Optional from types import FrameType from . import process_helper as ph from .logger_helper import color, colorize @@ -75,6 +75,7 @@ class Tester: self.tester_interface = tester_interface self.tests = self.determine_tests(config['tests'], model, case) self.active_runners = [] + self.pre_test_hook: Optional[Callable[[str, str], None]] = None @staticmethod def wildcard_match(pattern: str, potential_match: str) -> bool: @@ -203,6 +204,9 @@ class Tester: .format(log_dir)) os.makedirs(log_dir, exist_ok=True) + if self.pre_test_hook is not None: + self.pre_test_hook(test['model'], key) + was_success = self.run_test_case(test, key, log_dir) print("--- Test case {} of {}: '{}' {}." diff --git a/test/ros_test_runner.py b/test/ros_test_runner.py index db8e5a913d..11ca058bcf 100755 --- a/test/ros_test_runner.py +++ b/test/ros_test_runner.py @@ -7,6 +7,7 @@ import psutil # type: ignore import signal import subprocess import sys +import time from mavsdk_tests.integration_test_runner import test_runner, process_helper as ph, logger_helper from typing import Any, Dict, List, NoReturn @@ -45,8 +46,21 @@ class MicroXrceAgent: if self._verbose: print('Stopping micro-xrce-dds-agent') self._proc.kill() + self._proc.wait() self._proc = None + def restart(self): + """Force a fresh Agent process so DDS graph state does not leak across tests. + + The Agent retains writer entries from prior PX4 instances; a fresh PX4 reconnects + but the stale entries make count_publishers() return >0 before the new writers + are matched, breaking waitForFMU's two-phase discovery in px4-ros2-interface-lib. + """ + self.stop_process_if_started() + # Give the OS a moment to release the UDP port before rebinding. + time.sleep(0.2) + self.start_process() + class TesterInterfaceRos(test_runner.TesterInterface): @@ -187,9 +201,15 @@ def main() -> NoReturn: # Automatically start & stop the XRCE Agent if not running already micro_xrce_agent = MicroXrceAgent(args.verbose) - if not micro_xrce_agent.is_running(): + agent_managed_here = not micro_xrce_agent.is_running() + if agent_managed_here: micro_xrce_agent.start_process() + def restart_agent(_model: str, _case: str) -> None: + micro_xrce_agent.restart() + + tester.pre_test_hook = restart_agent + try: result = tester.run() finally: diff --git a/test/rostest_px4_run.sh b/test/rostest_px4_run.sh deleted file mode 100755 index e66e833e61..0000000000 --- a/test/rostest_px4_run.sh +++ /dev/null @@ -1,14 +0,0 @@ -#!/usr/bin/env bash - -DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd ) -PX4_SRC_DIR=${DIR}/.. - -source /opt/ros/${ROS_DISTRO:-kinetic}/setup.bash -source ${PX4_SRC_DIR}/Tools/simulation/gazebo-classic/setup_gazebo.bash ${PX4_SRC_DIR} ${PX4_SRC_DIR}/build/px4_sitl_default - -export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:${PX4_SRC_DIR}:${PX4_SRC_DIR}/Tools/simulation/gazebo-classic/sitl_gazebo-classic - -export ROS_LOG_DIR="$HOME/.ros/ros_logs" -mkdir -p "$ROS_LOG_DIR" - -rostest px4 "$@"