diff --git a/.github/workflows/sync_to_px4_msgs.yml b/.github/workflows/sync_to_px4_msgs.yml new file mode 100644 index 0000000000..eae00f3b3f --- /dev/null +++ b/.github/workflows/sync_to_px4_msgs.yml @@ -0,0 +1,62 @@ +name: Sync ROS 2 messages to px4_msgs +on: + push: + branches: + - 'main' + - 'stable' + - 'beta' + - 'release/**' + paths: + - 'msg/**' + - 'srv/**' + workflow_dispatch: + +permissions: + contents: read + +jobs: + sync_to_px4_msgs: + if: github.repository == 'PX4/PX4-Autopilot' + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] + steps: + - name: Checkout PX4 repo + uses: actions/checkout@v4 + + - name: Setup git credentials + run: | + git config --global user.name "${{ secrets.PX4BUILDBOT_USER }}" + git config --global user.email "${{ secrets.PX4BUILDBOT_EMAIL }}" + + - name: Clone PX4_msgs repo + run: | + git clone https://${{ secrets.PX4BUILTBOT_PERSONAL_ACCESS_TOKEN }}@github.com/PX4/px4_msgs.git + + - name: Check out the same branch as the PX4 repo + run: | + cd px4_msgs + if git checkout ${{ github.ref_name }}; then + echo "Checked out existing branch" + else + git checkout -b ${{ github.ref_name }} + fi + + - name: Copy ROS 2 messages + run: | + rm -f px4_msgs/msg/*.msg + rm -f px4_msgs/msg/versioned/*.msg + rm -f px4_msgs/srv/*.srv + rm -f px4_msgs/srv/versioned/*.srv + cp msg/*.msg px4_msgs/msg/ + cp msg/versioned/*.msg px4_msgs/msg/ || true + cp srv/*.srv px4_msgs/srv/ + cp srv/versioned/*.srv px4_msgs/srv/ || true + + - name: Commit and push changes + run: | + cd px4_msgs + git status + git add . + git commit -a -m "Update to PX4 ${{ github.sha }}" || true + git push origin ${{ github.ref_name }} || true + cd .. + rm -rf px4_msgs diff --git a/Jenkinsfile b/Jenkinsfile index fb092cd83d..b8f694e5d6 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -220,36 +220,6 @@ pipeline { } } - stage('PX4 ROS msgs') { - agent { - docker { image 'px4io/px4-dev-base-focal:2021-08-18' } - } - steps { - sh('export') - sh('make distclean; git clean -ff -x -d .') - withCredentials([usernamePassword(credentialsId: 'px4buildbot_github_personal_token', passwordVariable: 'GIT_PASS', usernameVariable: 'GIT_USER')]) { - sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/px4_msgs.git") - // 'main' branch - sh('rm -f px4_msgs/msg/*.msg') - sh('rm -f px4_msgs/msg/versioned/*.msg') - sh('rm -f px4_msgs/srv/*.srv') - sh('rm -f px4_msgs/srv/versioned/*.srv') - sh('cp msg/*.msg px4_msgs/msg/') - sh('cp msg/versioned/*.msg px4_msgs/msg/ || true') - sh('cp srv/*.srv px4_msgs/srv/') - sh('cp srv/versioned/*.srv px4_msgs/srv/ || true') - sh('cd px4_msgs; git status; git add .; git commit -a -m "Update message definitions `date`" || true') - sh('cd px4_msgs; git push origin main || true') - sh('rm -rf px4_msgs') - } - } - when { - anyOf { - branch 'main' - } - } - } - stage('S3') { agent { docker { image 'px4io/px4-dev-base-focal:2021-08-18' } diff --git a/Tools/process_sensor_caldata.py b/Tools/process_sensor_caldata.py index c0c656e015..d976d31460 100755 --- a/Tools/process_sensor_caldata.py +++ b/Tools/process_sensor_caldata.py @@ -1675,7 +1675,7 @@ baro_0_x_resample = fit_coef_baro_0_x(temp_rel_resample) plt.figure(13,figsize=(20,13)) # draw plots -plt.plot(sensor_baro_0['temperature'],100*sensor_baro_0['pressure']-100*median_pressure,'b') +plt.plot(sensor_baro_0['temperature'],sensor_baro_0['pressure']-median_pressure,'b') plt.plot(temp_resample,baro_0_x_resample,'r') plt.title('Baro 0 ({}) Bias vs Temperature'.format(baro_0_params['TC_B0_ID'])) plt.ylabel('Z bias (Pa)') @@ -1736,7 +1736,7 @@ if num_baros >= 2: plt.figure(14,figsize=(20,13)) # draw plots - plt.plot(sensor_baro_1['temperature'],100*sensor_baro_1['pressure']-100*median_pressure,'b') + plt.plot(sensor_baro_1['temperature'],sensor_baro_1['pressure']-median_pressure,'b') plt.plot(temp_resample,baro_1_x_resample,'r') plt.title('Baro 1 ({}) Bias vs Temperature'.format(baro_1_params['TC_B1_ID'])) plt.ylabel('Z bias (Pa)') @@ -1797,7 +1797,7 @@ if num_baros >= 3: plt.figure(15,figsize=(20,13)) # draw plots - plt.plot(sensor_baro_2['temperature'],100*sensor_baro_2['pressure']-100*median_pressure,'b') + plt.plot(sensor_baro_2['temperature'],sensor_baro_2['pressure']-median_pressure,'b') plt.plot(temp_resample,baro_2_x_resample,'r') plt.title('Baro 2 ({}) Bias vs Temperature'.format(baro_2_params['TC_B2_ID'])) plt.ylabel('Z bias (Pa)') @@ -1853,7 +1853,7 @@ if num_baros >= 4: plt.figure(16,figsize=(20,13)) # draw plots - plt.plot(sensor_baro_3['temperature'],100*sensor_baro_3['pressure']-100*median_pressure,'b') + plt.plot(sensor_baro_3['temperature'],sensor_baro_3['pressure']-median_pressure,'b') plt.plot(temp_resample,baro_3_x_resample,'r') plt.title('Baro 3 ({}) Bias vs Temperature'.format(baro_3_params['TC_B3_ID'])) plt.ylabel('Z bias (Pa)') diff --git a/boards/auterion/fmu-v6s/default.px4board b/boards/auterion/fmu-v6s/default.px4board index 78c3cb878c..cf1f0f2915 100644 --- a/boards/auterion/fmu-v6s/default.px4board +++ b/boards/auterion/fmu-v6s/default.px4board @@ -85,7 +85,6 @@ CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SD_BENCH=y -CONFIG_SYSTEMCMDS_SERIAL_TEST=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y diff --git a/docs/assets/hardware/complete_vehicles/modalai_starling/d0005_compute_wiring_d.jpg b/docs/assets/hardware/complete_vehicles/modalai_starling/d0005_compute_wiring_d.jpg deleted file mode 100644 index 95773124e4..0000000000 Binary files a/docs/assets/hardware/complete_vehicles/modalai_starling/d0005_compute_wiring_d.jpg and /dev/null differ diff --git a/docs/assets/hardware/complete_vehicles/modalai_starling/mrb_d0005_4_v2_c6_m22__callouts_a.jpg b/docs/assets/hardware/complete_vehicles/modalai_starling/mrb_d0005_4_v2_c6_m22__callouts_a.jpg deleted file mode 100644 index baa39c19c6..0000000000 Binary files a/docs/assets/hardware/complete_vehicles/modalai_starling/mrb_d0005_4_v2_c6_m22__callouts_a.jpg and /dev/null differ diff --git a/docs/assets/hardware/complete_vehicles/modalai_starling/radio-1.png b/docs/assets/hardware/complete_vehicles/modalai_starling/radio-1.png deleted file mode 100644 index 1c99ea15ae..0000000000 Binary files a/docs/assets/hardware/complete_vehicles/modalai_starling/radio-1.png and /dev/null differ diff --git a/docs/assets/hardware/complete_vehicles/modalai_starling/radio-2.png b/docs/assets/hardware/complete_vehicles/modalai_starling/radio-2.png deleted file mode 100644 index b5298b55b8..0000000000 Binary files a/docs/assets/hardware/complete_vehicles/modalai_starling/radio-2.png and /dev/null differ diff --git a/docs/assets/hardware/complete_vehicles/modalai_starling/screenshot-boot.png b/docs/assets/hardware/complete_vehicles/modalai_starling/screenshot-boot.png deleted file mode 100644 index d74c6d439c..0000000000 Binary files a/docs/assets/hardware/complete_vehicles/modalai_starling/screenshot-boot.png and /dev/null differ diff --git a/docs/assets/hardware/complete_vehicles/modalai_starling/starling-photo.png b/docs/assets/hardware/complete_vehicles/modalai_starling/starling-photo.png deleted file mode 100644 index a9cf9b985e..0000000000 Binary files a/docs/assets/hardware/complete_vehicles/modalai_starling/starling-photo.png and /dev/null differ diff --git a/docs/en/advanced/neural_networks.md b/docs/en/advanced/neural_networks.md index 4f85ee7e63..91829f3a88 100644 --- a/docs/en/advanced/neural_networks.md +++ b/docs/en/advanced/neural_networks.md @@ -26,6 +26,10 @@ If you are looking for more resources to learn about the module, a website has b ## Neural Network PX4 Firmware +::: warning +This module requires Ubuntu 24.04 or newer (it is not supported in Ubuntu 22.04). +::: + The module has been tested on a number of configurations, which can be build locally using the commands: ```sh diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index b140b398ab..a9a13e4984 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -14357,22 +14357,6 @@ Defines which RC_MAP_AUXn parameter maps the manual control channel used to enab | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 6 | | 0 | -### FW_AT_START (`INT32`) {#FW_AT_START} - -Start the autotuning sequence. - -WARNING: this will inject steps to the rate controller -and can be dangerous. Only activate if you know what you -are doing, and in a safe environment. -Any motion of the remote stick will abort the signal -injection and reset this parameter -Best is to perform the identification in position or -hold mode. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------------ | ---- | -|   | | | | Disabled (0) | - ### FW_AT_SYSID_F0 (`FLOAT`) {#FW_AT_SYSID_F0} Start frequency of the injected signal. @@ -14456,24 +14440,6 @@ Desired angular rate closed-loop rise time. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.01 | 0.5 | | 0.14 | s | -### MC_AT_START (`INT32`) {#MC_AT_START} - -Start the autotuning sequence. - -WARNING: this will inject steps to the rate controller -and can be dangerous. Only activate if you know what you -are doing, and in a safe environment. -Any motion of the remote stick will abort the signal -injection and reset this parameter -Best is to perform the identification in position or -hold mode. -Increase the amplitude of the injected signal using -MC_AT_SYSID_AMP for more signal/noise ratio - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------------ | ---- | -|   | | | | Disabled (0) | - ### MC_AT_SYSID_AMP (`FLOAT`) {#MC_AT_SYSID_AMP} Amplitude of the injected signal. @@ -17097,6 +17063,16 @@ EKF2 enable. | ------ | -------- | -------- | --------- | ----------- | ---- | |   | | | | Enabled (1) | +### EKF2_ENGINE_WRM (`INT32`) {#EKF2_ENGINE_WRM} + +Enable constant position fusion during engine warmup. + +When enabled, constant position fusion is enabled when the vehicle is landed and armed. This is intended for IC engine warmup (e.g., fuel engines on catapult) to allow mode transitions to auto/takeoff despite vibrations from running engines. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------------ | ---- | +|   | | | | Disabled (0) | + ### EKF2_EVA_NOISE (`FLOAT`) {#EKF2_EVA_NOISE} Measurement noise for vision angle measurements. diff --git a/docs/en/mavlink/standard_modes.md b/docs/en/mavlink/standard_modes.md index eabfe8d15e..87d4cd2545 100644 --- a/docs/en/mavlink/standard_modes.md +++ b/docs/en/mavlink/standard_modes.md @@ -2,7 +2,7 @@ -PX4 implements the MAVLink [Standard Modes Protocol](https://mavlink.io/en/services/standard_modes.md) from PX4 v1.15, with a corresponding implementation in QGroundControl Daily builds (and future release builds). +PX4 implements the MAVLink [Standard Modes Protocol](https://mavlink.io/en/services/standard_modes.html) from PX4 v1.15, with a corresponding implementation in QGroundControl Daily builds (and future release builds). The protocol allows you to discover all flight modes available to the vehicle, including PX4 External modes created using the [PX4 ROS 2 Control Interface](../ros2/px4_ros2_control_interface.md), and get or set the current mode. diff --git a/docs/en/msg_docs/VehicleCommand.md b/docs/en/msg_docs/VehicleCommand.md index 7f91701614..1b1b3ed658 100644 --- a/docs/en/msg_docs/VehicleCommand.md +++ b/docs/en/msg_docs/VehicleCommand.md @@ -69,6 +69,7 @@ uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute. |a uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # Motor test command. |Instance (@range 1, )|throttle type|throttle|timeout [s]|Motor count|Test order|Unused| uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight. |inverted (0=normal, 1=inverted)|Unused|Unused|Unused|Unused|Unused|Unused| uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper. +uint16 VEHICLE_CMD_DO_AUTOTUNE_ENABLE = 212 # Enable autotune module. |1 to enable|Unused|Unused|Unused|Unused|Unused|Unused| uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight. |[m] Camera trigger distance|Shutter integration time (ms)|Unused|Unused|Unused|Unused|Unused| uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)|q2 - quaternion param #2, x (0 in null-rotation)|q3 - quaternion param #3, y (0 in null-rotation)|q4 - quaternion param #4, z (0 in null-rotation)|Unused|Unused|Unused| uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| diff --git a/docs/ko/config_fw/airspeed_scale_handling.md b/docs/ko/config_fw/airspeed_scale_handling.md index 831edd4144..02f745fc72 100644 --- a/docs/ko/config_fw/airspeed_scale_handling.md +++ b/docs/ko/config_fw/airspeed_scale_handling.md @@ -78,13 +78,19 @@ Follow these steps: 1. **Set an Initial Scale** - Use a conservative starting point: set the CAS scale (`ASPD_SCALE_n`) slightly under 1.0 (for example 0.95). - This biases the system toward over-speed rather than under-speed, reducing stall risk. + Set the CAS scale (`ASPD_SCALE_n`) to 1.0 (the default value). + When the scale is at exactly 1.0, PX4 automatically accelerates the learning process during the first 5 minutes of flight, allowing faster convergence to the correct scale value. 2. **Perform a Flight** After takeoff, place the vehicle in loiter for about 15 minutes to allow the scale estimation to converge. + ::: tip + Flying in circles (loiter/hold mode) is important as the scale-validation algorithm requires the aircraft to pass through multiple heading segments (12 segments covering all compass directions). + If these heading segments aren’t completed, PX4 cannot validate the estimated scale. + +::: + 3. **Check Scale Convergence** After the flight, review the estimated scale in logs. diff --git a/docs/ko/flight_modes_fw/mission.md b/docs/ko/flight_modes_fw/mission.md index 5930bbf95f..0d5f695af6 100644 --- a/docs/ko/flight_modes_fw/mission.md +++ b/docs/ko/flight_modes_fw/mission.md @@ -167,6 +167,10 @@ Mission Items: - [MAV_CMD_OBLIQUE_SURVEY](https://mavlink.io/en/messages/common.html#MAV_CMD_OBLIQUE_SURVEY) - [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM) - [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS) +- [MAV_CMD_DO_AUTOTUNE_ENABLE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_AUTOTUNE_ENABLE) + - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. + - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0). + Instead, the axis bitmask defined by [`FW_AT_AXES`](../advanced_config/parameter_reference.md#FW_AT_AXES) is used. GeoFence Definitions diff --git a/docs/ko/flight_modes_mc/mission.md b/docs/ko/flight_modes_mc/mission.md index 778c22f386..313aabcb18 100644 --- a/docs/ko/flight_modes_mc/mission.md +++ b/docs/ko/flight_modes_mc/mission.md @@ -171,6 +171,9 @@ Mission Items: - [MAV_CMD_NAV_VTOL_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_TAKEOFF) - `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (transition heading) is ignored. Instead the heading to the next waypoint is used for the transition heading. +- [MAV_CMD_DO_AUTOTUNE_ENABLE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_AUTOTUNE_ENABLE) + - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. + - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0) . GeoFence Definitions diff --git a/docs/uk/config_fw/airspeed_scale_handling.md b/docs/uk/config_fw/airspeed_scale_handling.md index 831edd4144..02f745fc72 100644 --- a/docs/uk/config_fw/airspeed_scale_handling.md +++ b/docs/uk/config_fw/airspeed_scale_handling.md @@ -78,13 +78,19 @@ Follow these steps: 1. **Set an Initial Scale** - Use a conservative starting point: set the CAS scale (`ASPD_SCALE_n`) slightly under 1.0 (for example 0.95). - This biases the system toward over-speed rather than under-speed, reducing stall risk. + Set the CAS scale (`ASPD_SCALE_n`) to 1.0 (the default value). + When the scale is at exactly 1.0, PX4 automatically accelerates the learning process during the first 5 minutes of flight, allowing faster convergence to the correct scale value. 2. **Perform a Flight** After takeoff, place the vehicle in loiter for about 15 minutes to allow the scale estimation to converge. + ::: tip + Flying in circles (loiter/hold mode) is important as the scale-validation algorithm requires the aircraft to pass through multiple heading segments (12 segments covering all compass directions). + If these heading segments aren’t completed, PX4 cannot validate the estimated scale. + +::: + 3. **Check Scale Convergence** After the flight, review the estimated scale in logs. diff --git a/docs/uk/flight_modes_fw/mission.md b/docs/uk/flight_modes_fw/mission.md index f8b6aacaea..57ce4be8f6 100644 --- a/docs/uk/flight_modes_fw/mission.md +++ b/docs/uk/flight_modes_fw/mission.md @@ -167,6 +167,10 @@ PX4 "приймає" наступні команди місії MAVLink у ре - [MAV_CMD_OBLIQUE_SURVEY](https://mavlink.io/en/messages/common.html#MAV_CMD_OBLIQUE_SURVEY) - [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM) - [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS) +- [MAV_CMD_DO_AUTOTUNE_ENABLE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_AUTOTUNE_ENABLE) + - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. + - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0). + Instead, the axis bitmask defined by [`FW_AT_AXES`](../advanced_config/parameter_reference.md#FW_AT_AXES) is used. Визначення GeoFence diff --git a/docs/uk/flight_modes_mc/mission.md b/docs/uk/flight_modes_mc/mission.md index 96cf5c7306..1743800936 100644 --- a/docs/uk/flight_modes_mc/mission.md +++ b/docs/uk/flight_modes_mc/mission.md @@ -171,6 +171,9 @@ PX4 "приймає" наступні команди місії MAVLink у ре - [MAV_CMD_NAV_VTOL_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_TAKEOFF) - `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (заголовок переходу) ігнорується. Замість цього напрямок до наступної маршрутної точки використовується для переходу. +- [MAV_CMD_DO_AUTOTUNE_ENABLE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_AUTOTUNE_ENABLE) + - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. + - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0) . Визначення GeoFence diff --git a/docs/zh/config_fw/airspeed_scale_handling.md b/docs/zh/config_fw/airspeed_scale_handling.md index 831edd4144..02f745fc72 100644 --- a/docs/zh/config_fw/airspeed_scale_handling.md +++ b/docs/zh/config_fw/airspeed_scale_handling.md @@ -78,13 +78,19 @@ Follow these steps: 1. **Set an Initial Scale** - Use a conservative starting point: set the CAS scale (`ASPD_SCALE_n`) slightly under 1.0 (for example 0.95). - This biases the system toward over-speed rather than under-speed, reducing stall risk. + Set the CAS scale (`ASPD_SCALE_n`) to 1.0 (the default value). + When the scale is at exactly 1.0, PX4 automatically accelerates the learning process during the first 5 minutes of flight, allowing faster convergence to the correct scale value. 2. **Perform a Flight** After takeoff, place the vehicle in loiter for about 15 minutes to allow the scale estimation to converge. + ::: tip + Flying in circles (loiter/hold mode) is important as the scale-validation algorithm requires the aircraft to pass through multiple heading segments (12 segments covering all compass directions). + If these heading segments aren’t completed, PX4 cannot validate the estimated scale. + +::: + 3. **Check Scale Convergence** After the flight, review the estimated scale in logs. diff --git a/docs/zh/flight_modes_fw/mission.md b/docs/zh/flight_modes_fw/mission.md index e3d9dcb654..ee19cd8b22 100644 --- a/docs/zh/flight_modes_fw/mission.md +++ b/docs/zh/flight_modes_fw/mission.md @@ -167,6 +167,10 @@ Mission Items: - [MAV_CMD_OBLIQUE_SURVEY](https://mavlink.io/en/messages/common.html#MAV_CMD_OBLIQUE_SURVEY) - [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM) - [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS) +- [MAV_CMD_DO_AUTOTUNE_ENABLE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_AUTOTUNE_ENABLE) + - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. + - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0). + Instead, the axis bitmask defined by [`FW_AT_AXES`](../advanced_config/parameter_reference.md#FW_AT_AXES) is used. GeoFence Definitions diff --git a/docs/zh/flight_modes_mc/mission.md b/docs/zh/flight_modes_mc/mission.md index 7b8b03cb2d..9d30914129 100644 --- a/docs/zh/flight_modes_mc/mission.md +++ b/docs/zh/flight_modes_mc/mission.md @@ -171,6 +171,9 @@ Mission Items: - [MAV_CMD_NAV_VTOL_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_TAKEOFF) - `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (transition heading) is ignored. Instead the heading to the next waypoint is used for the transition heading. +- [MAV_CMD_DO_AUTOTUNE_ENABLE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_AUTOTUNE_ENABLE) + - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. + - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0) . GeoFence Definitions