Merge branch 'main' into maetugr/fix-ros-integration-ci

This commit is contained in:
Ramon Roche
2026-05-14 14:44:02 -07:00
committed by GitHub
80 changed files with 2582 additions and 2504 deletions
-73
View File
@@ -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
+4 -1
View File
@@ -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
@@ -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
)
+10
View File
@@ -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
@@ -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
@@ -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
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
@@ -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
@@ -37,7 +37,6 @@ then
set INA_CONFIGURED yes
fi
if param compare SENS_EN_INA228 1
then
# Start Digital power monitors
+5 -3
View File
@@ -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
-2
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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)
File diff suppressed because it is too large Load Diff
+2 -1
View File
@@ -52,7 +52,8 @@ RC controllers will use different sticks for throttle and yaw [based on their mo
- _Arm:_ Left-stick to right, right-stick to bottom.
- _Disarm:_ Left-stick to left, right-stick to the bottom.
Note that disarming in any altitude controlled mode is only possible after landing was detected. In manually piloted modes without altitude control Stabilized, Acro, Manual it's always possible to disarm using gestures or buttons also in flight.
Note that disarming in any altitude controlled mode is only possible after landing was detected.
In manually piloted modes without altitude control, such as Stabilized, Acro, and Manual, it's always possible to disarm using gestures or buttons — even in flight.
| Parameter | Description |
| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------ |
+3 -3
View File
@@ -241,10 +241,10 @@ Triggers on either of:
At least a warning is emitted, additional failsafe actions can be configured using [COM_GNSSLOSS_ACT](#COM_GNSSLOSS_ACT).
Loss of a single GPS when none are required is handled by other GPS health checks.
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------- |
| <a id="SYS_HAS_NUM_GNSS"></a>[SYS_HAS_NUM_GNSS](../advanced_config/parameter_reference.md#SYS_HAS_NUM_GNSS) | Number of usable GNSS receivers required for arming and flight. If two are required then they also need to be consistent. |
| <a id="COM_GNSSLOSS_ACT"></a>[COM_GNSSLOSS_ACT](../advanced_config/parameter_reference.md#COM_GNSSLOSS_ACT) | Failsafe action when a GNSS failure is detected. Actions other than a warning also lead to arming being blocked. |
| <a id="COM_GNSSLOSS_ACT"></a>[COM_GNSSLOSS_ACT](../advanced_config/parameter_reference.md#COM_GNSSLOSS_ACT) | Failsafe action when a GNSS failure is detected. Actions other than a warning also lead to arming being blocked. |
## Offboard Loss Failsafe
+192 -192
View File
@@ -95,209 +95,209 @@ They are not build into the module, and hence are neither published or subscribe
::: details See messages
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [Ping](../msg_docs/Ping.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [InputRc](../msg_docs/InputRc.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [Vtx](../msg_docs/Vtx.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [Gripper](../msg_docs/Gripper.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [HomePositionV0](../msg_docs/HomePositionV0.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [SensorGyro](../msg_docs/SensorGyro.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)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [RaptorStatus](../msg_docs/RaptorStatus.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [EstimatorFusionControl](../msg_docs/EstimatorFusionControl.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [Mission](../msg_docs/Mission.md)
- [RangingBeacon](../msg_docs/RangingBeacon.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [Rpm](../msg_docs/Rpm.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.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)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [Event](../msg_docs/Event.md)
- [LedControl](../msg_docs/LedControl.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [EscEepromWrite](../msg_docs/EscEepromWrite.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [BatteryInfo](../msg_docs/BatteryInfo.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.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)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
- [VehicleStatusV3](../msg_docs/VehicleStatusV3.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [RegisterExtComponentRequestV1](../msg_docs/RegisterExtComponentRequestV1.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.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)
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.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)
- [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)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [EscReport](../msg_docs/EscReport.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.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)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [InputRc](../msg_docs/InputRc.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [EventV0](../msg_docs/EventV0.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [SensorTemp](../msg_docs/SensorTemp.md)
- [DeviceInformation](../msg_docs/DeviceInformation.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [RaptorInput](../msg_docs/RaptorInput.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [NeuralControl](../msg_docs/NeuralControl.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [GainCompression](../msg_docs/GainCompression.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
- [EscEepromRead](../msg_docs/EscEepromRead.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
:::
+20
View File
@@ -432,6 +432,26 @@ gz_bridge <command> [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 <command> [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)
+38 -36
View File
@@ -13,9 +13,9 @@ The flag comments are used as label for the failsafe state machine simulation
## Fields
| Name | Type | Unit [Frame] | Range/Enum | Description |
| ---------------------------------------- | -------- | ------------ | ---------- | ----------------------------------------------------------------------------------------- |
| timestamp | `uint64` | | | time since system start (microseconds) |
| Name | Type | Unit [Frame] | Range/Enum | Description |
| ---------------------------------------- | -------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------ |
| timestamp | `uint64` | | | time since system start (microseconds) |
| mode_req_angular_velocity | `uint32` | | |
| mode_req_attitude | `uint32` | | |
| mode_req_local_alt | `uint32` | | |
@@ -26,40 +26,41 @@ The flag comments are used as label for the failsafe state machine simulation
| mode_req_mission | `uint32` | | |
| mode_req_offboard_signal | `uint32` | | |
| mode_req_home_position | `uint32` | | |
| mode_req_wind_and_flight_time_compliance | `uint32` | | | if set, mode cannot be entered if wind or flight time limit exceeded |
| mode_req_prevent_arming | `uint32` | | | if set, cannot arm while in this mode |
| mode_req_wind_and_flight_time_compliance | `uint32` | | | if set, mode cannot be entered if wind or flight time limit exceeded |
| mode_req_prevent_arming | `uint32` | | | if set, cannot arm while in this mode |
| mode_req_manual_control | `uint32` | | |
| mode_req_other | `uint32` | | | other requirements, not covered above (for external modes) |
| angular_velocity_invalid | `bool` | | | Angular velocity invalid |
| attitude_invalid | `bool` | | | Attitude invalid |
| local_altitude_invalid | `bool` | | | Local altitude invalid |
| local_position_invalid | `bool` | | | Local position estimate invalid |
| local_position_invalid_relaxed | `bool` | | | Local position with reduced accuracy requirements invalid (e.g. flying with optical flow) |
| local_velocity_invalid | `bool` | | | Local velocity estimate invalid |
| global_position_invalid | `bool` | | | Global position estimate invalid |
| global_position_invalid_relaxed | `bool` | | | Global position estimate invalid with relaxed accuracy requirements |
| auto_mission_missing | `bool` | | | No mission available |
| offboard_control_signal_lost | `bool` | | | Offboard signal lost |
| home_position_invalid | `bool` | | | No home position available |
| manual_control_signal_lost | `bool` | | | Manual control (RC) signal lost |
| gcs_connection_lost | `bool` | | | GCS connection lost |
| battery_warning | `uint8` | | | Battery warning level (see BatteryStatus.msg) |
| battery_low_remaining_time | `bool` | | | Low battery based on remaining flight time |
| battery_unhealthy | `bool` | | | Battery unhealthy |
| fd_critical_failure | `bool` | | | Critical failure (attitude limit exceeded, or external ATS) |
| fd_esc_arming_failure | `bool` | | | ESC failed to arm |
| fd_imbalanced_prop | `bool` | | | Imbalanced propeller detected |
| fd_motor_failure | `bool` | | | Motor failure |
| fd_alt_loss | `bool` | | | Uncommanded altitude loss (rotary-wing, altitude-controlled flight) |
| geofence_breached | `bool` | | | Geofence breached (one or multiple) |
| mission_failure | `bool` | | | Mission failure |
| vtol_fixed_wing_system_failure | `bool` | | | vehicle in fixed-wing system failure failsafe mode (after quad-chute) |
| wind_limit_exceeded | `bool` | | | Wind limit exceeded |
| flight_time_limit_exceeded | `bool` | | | Maximum flight time exceeded |
| position_accuracy_low | `bool` | | | Position estimate has dropped below threshold, but is currently still declared valid |
| navigator_failure | `bool` | | | Navigator failed to execute a mode |
| parachute_unhealthy | `bool` | | | Parachute system missing or unhealthy |
| remote_id_unhealthy | `bool` | | | Remote ID (Open Drone ID) system missing or unhealthy |
| mode_req_other | `uint32` | | | other requirements, not covered above (for external modes) |
| angular_velocity_invalid | `bool` | | | Angular velocity invalid |
| attitude_invalid | `bool` | | | Attitude invalid |
| local_altitude_invalid | `bool` | | | Local altitude invalid |
| local_position_invalid | `bool` | | | Local position estimate invalid |
| local_position_invalid_relaxed | `bool` | | | Local position with reduced accuracy requirements invalid (e.g. flying with optical flow) |
| local_velocity_invalid | `bool` | | | Local velocity estimate invalid |
| global_position_invalid | `bool` | | | Global position estimate invalid |
| global_position_invalid_relaxed | `bool` | | | Global position estimate invalid with relaxed accuracy requirements |
| auto_mission_missing | `bool` | | | No mission available |
| offboard_control_signal_lost | `bool` | | | Offboard signal lost |
| home_position_invalid | `bool` | | | No home position available |
| manual_control_signal_lost | `bool` | | | Manual control (RC) signal lost |
| gcs_connection_lost | `bool` | | | GCS connection lost |
| battery_warning | `uint8` | | | Battery warning level (see BatteryStatus.msg) |
| battery_low_remaining_time | `bool` | | | Low battery based on remaining flight time |
| battery_unhealthy | `bool` | | | Battery unhealthy |
| fd_critical_failure | `bool` | | | Critical failure (attitude limit exceeded, or external ATS) |
| fd_esc_arming_failure | `bool` | | | ESC failed to arm |
| fd_imbalanced_prop | `bool` | | | Imbalanced propeller detected |
| fd_motor_failure | `bool` | | | Motor failure |
| fd_alt_loss | `bool` | | | Uncommanded altitude loss (rotary-wing, altitude-controlled flight) |
| geofence_breached | `bool` | | | Geofence breached (one or multiple) |
| mission_failure | `bool` | | | Mission failure |
| vtol_fixed_wing_system_failure | `bool` | | | vehicle in fixed-wing system failure failsafe mode (after quad-chute) |
| wind_limit_exceeded | `bool` | | | Wind limit exceeded |
| flight_time_limit_exceeded | `bool` | | | Maximum flight time exceeded |
| position_accuracy_low | `bool` | | | Position estimate has dropped below threshold, but is currently still declared valid |
| navigator_failure | `bool` | | | Navigator failed to execute a mode |
| parachute_unhealthy | `bool` | | | Parachute system missing or unhealthy |
| remote_id_unhealthy | `bool` | | | Remote ID (Open Drone ID) system missing or unhealthy |
| gnss_lost | `bool` | | | Active GNSS count dropped below SYS_HAS_NUM_GNSS, or two receivers report inconsistent positions |
## Source Message
@@ -131,6 +132,7 @@ bool position_accuracy_low # Position estimate has dropped below thre
bool navigator_failure # Navigator failed to execute a mode
bool parachute_unhealthy # Parachute system missing or unhealthy
bool remote_id_unhealthy # Remote ID (Open Drone ID) system missing or unhealthy
bool gnss_lost # Active GNSS count dropped below SYS_HAS_NUM_GNSS, or two receivers report inconsistent positions
```
:::
+2
View File
@@ -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.
<!-- Links for table above -->
[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
+53
View File
@@ -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)
+286 -58
View File
@@ -13,122 +13,350 @@ const { site } = useData();
</div>
</div>
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).
- <Badge type="warning" text="Experimental" /> 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`).
- <Badge type="warning" text="Experimental" /> 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<N>_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) <!-- CHECK is this version and add PR link (or fix up doc version tag and move this) -->
- **[New Hardware]** boards: [RadiolinkPIX6 FC](../flight_controller/radiolink_pix6.md) <!-- CHECK is this version and add PR! -->
- **[New Hardware]** boards: [AP-H743-R1 FC](../flight_controller/x-mav_ap-h743r1.md) <!-- CHECK is this version and add PR! -->
#### New Flight Controllers
<!--
- [Radiolink PIX6](../flight_controller/radiolink_pix6.md).
([PX4-Autopilot#25562](https://github.com/PX4/PX4-Autopilot/pull/25562))
- [CUAV X25-Evo](../flight_controller/cuav_x25-evo.md).
([PX4-Autopilot#25176](https://github.com/PX4/PX4-Autopilot/pull/25176))
- [Accton Godwit GA1](../flight_controller/accton-godwit_ga1.md).
([PX4-Autopilot#25411](https://github.com/PX4/PX4-Autopilot/pull/25411))
- Kakute H7 dual-IMU build target (no English docs page).
- NarinFC-H7 (no English docs page).
- ESP32 generic-target support, sponsored by AutonoSky (no English docs page; experimental).
#### New Build Targets for Existing Hardware
- `cuav/fmu-v6x` build target for the [CUAV Pixhawk V6X](../flight_controller/cuav_pixhawk_v6x.md).
- `auterion/fmu-v6x` build target for the Auterion FMU-v6x.
#### New CAN Peripherals & Vehicle Platforms
- MR-CANHUBK344 NXP B3RB Rover platform.
([PX4-Autopilot#23897](https://github.com/PX4/PX4-Autopilot/pull/23897))
- NXP MR-Tropic target with imxrt-related fixes.
([PX4-Autopilot#26052](https://github.com/PX4/PX4-Autopilot/pull/26052))
- ARK X20 and F9P GPS receivers.
([PX4-Autopilot#25149](https://github.com/PX4/PX4-Autopilot/pull/25149))
- ARK DIST distance sensor.
#### Existing Boards: Improvements
- FMU-v6xRT: V6XRT001 and V6XRT002 sensor sets, LIS2MDL and BMM350 magnetometer support, DTCM added to heap.
([PX4-Autopilot#25733](https://github.com/PX4/PX4-Autopilot/pull/25733))
- FMU-v6s: PCA9685 PWM expander driver, INA226 / INA228 / INA238 power-monitor support, HSE used as the RTC clock, init script reordered to start internal sensors first.
- ARK FPV: rover board variant, payload-deliverer module, and `encrypted_logs` flash savings (FW and VTOL stripped).
([PX4-Autopilot#25319](https://github.com/PX4/PX4-Autopilot/pull/25319), [PX4-Autopilot#25322](https://github.com/PX4/PX4-Autopilot/pull/25322))
- ARK SCH16T driver updated for new Murata modules.
([PX4-Autopilot#24029](https://github.com/PX4/PX4-Autopilot/pull/24029))
- mRO PixracerPro: enable additional UARTs.
([PX4-Autopilot#22516](https://github.com/PX4/PX4-Autopilot/pull/22516))
- 3DR Control Zero H7 OEM Rev G: MTD driver fix and missing module that prevented USB enumeration.
([PX4-Autopilot#25015](https://github.com/PX4/PX4-Autopilot/pull/25015))
- ESP32: PWM register updates correctly on change.
([PX4-Autopilot#25653](https://github.com/PX4/PX4-Autopilot/pull/25653))
- Tropic-Community baseboard (Teensy 4.1): PX4 config refresh, DTCM moved to heap with vectors in ITCM.
### Common
- [QGroundControl 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 a number of releases. ([PX4-Autopilot#25032: build: romf: fix generation of rc.board_bootloader_upgrade](https://github.com/PX4/PX4-Autopilot/pull/25032)).
-->
- [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
<!--
- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW).
For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
-->
- <Badge type="warning" text="Experimental" /> [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
<!--
- [Barometer auto-calibration](../advanced_config/parameter_reference.md#SENS_BAR_AUTOCAL) can calibrate offsets against GNSS height when GNSS is the height reference, enabled by default.
([PX4-Autopilot#24859](https://github.com/PX4/PX4-Autopilot/pull/24859))
- Septentrio GNSS resilience reporting (jamming, spoofing, authentication state) is now exposed in PX4.
([PX4-Autopilot#25012](https://github.com/PX4/PX4-Autopilot/pull/25012))
- EKF2 GPS checks include a GPS fix type validation bit.
([PX4-Autopilot#25215](https://github.com/PX4/PX4-Autopilot/pull/25215))
- EKF2 GNSS aiding: dedicated `gnss_fault` flag added to `EstimatorStatusFlags`; lat/lon/vel fusion is disabled on `gnss_hgt_fault`; hysteresis added for re-enabling fusion; GNSS-based altitude reset is suppressed in dead-reckoning mode.
- EKF2 range fusion: skip unhealthy samples while respecting timeout ([PX4-Autopilot#25634](https://github.com/PX4/PX4-Autopilot/pull/25634)); reject bad measurements during `bad_acc_vertical` ([PX4-Autopilot#25636](https://github.com/PX4/PX4-Autopilot/pull/25636)).
- EKF2 mag: post-takeoff yaw reset is never skipped; mag heading and declination updates no longer perturb the xy gyro biases.
- EKF2 gravity: tilt alignment accelerated; gravity fusion start now uses an accel low-pass instead of peak hold.
- EKF2 airspeed/wind: distinguish airspeed source so wind dead-reckoning logic can use a synthetic airspeed.
- External heading update via `MAV_CMD_EXTERNAL_ATTITUDE_ESTIMATE` is now consumed by EKF2.
- RTCM telemetry stream now also published for UAVCAN GNSS receivers.
([PX4-Autopilot#25315](https://github.com/PX4/PX4-Autopilot/pull/25315))
- EKF2 GNSS reset improvements.
([PX4-Autopilot#25297](https://github.com/PX4/PX4-Autopilot/pull/25297))
### Sensors
- Add [sbgECom INS driver](../sensor/sbgecom.md) ([PX4-Autopilot#24137](https://github.com/PX4/PX4-Autopilot/pull/24137))
- Quick magnetometer calibration now supports specifying an arbitrary initial heading ([PX4-Autopilot#24637](https://github.com/PX4/PX4-Autopilot/pull/24637))
-->
- 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) <!-- Listed in https://docs.px4.io/main/en/sim_sih/#compatibility : Check the PRs -->
- 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)
<Badge type="warning" text="Experimental" />
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
<!--
- MAVFTP hardening: rejects path-traversal sequences in FTP operations and validates sessions in FTP write/burst.
- MAVLink v1 is now opt-in via [`MAV_PROTO_VER`](../advanced_config/parameter_reference.md#MAV_PROTO_VER).
([PX4-Autopilot#25583](https://github.com/PX4/PX4-Autopilot/pull/25583))
- Extended `MISSION_CURRENT` message implemented (populates `mission_state` and related fields per [mavlink/mavlink#1869](https://github.com/mavlink/mavlink/pull/1869)).
([PX4-Autopilot#25034](https://github.com/PX4/PX4-Autopilot/pull/25034))
- `MAV_CMD_REQUEST_MESSAGE` supported for `MESSAGE_INTERVAL`.
([PX4-Autopilot#25460](https://github.com/PX4/PX4-Autopilot/pull/25460))
- The low-bandwidth stream profile includes additional important streams with updated rates.
([PX4-Autopilot#25524](https://github.com/PX4/PX4-Autopilot/pull/25524))
- Parameter transmission throttled on low-bandwidth links.
([PX4-Autopilot#25126](https://github.com/PX4/PX4-Autopilot/pull/25126))
- Set system clock from `SYSTEM_TIME`.
([PX4-Autopilot#24807](https://github.com/PX4/PX4-Autopilot/pull/24807))
- Hardfault streaming over MAVLink option added.
- MAVLink fuzz test added.
### RC
- Parse ELRS Status and Link Statistics TX messages in the CRSF parser.
- Removed the hardcoded 1 percent deadzone on RC channels 1 to 8.
([PX4-Autopilot#25502](https://github.com/PX4/PX4-Autopilot/pull/25502))
- ManualControlSelector reworked: robust timeout checks, unified validity conditions, simplified prioritization, and an option to prioritize RC or MAVLink with fallback.
- `COM_RC_IN_MODE` extended with source-ID ascending and descending priority modes; documentation rewritten.
- Payload power switch generalized: optional 3-way switch, allowed on boards beyond ARK FPV, with unit tests.
### Multi-Rotor
- Removed parameters `MPC_{XY/Z/YAW}_MAN_EXPO` and use default value instead, as they were not deemed necessary anymore. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
- Renamed `MPC_HOLD_DZ` to `MAN_DEADZONE` to have it globally available in modes that allow for a dead zone. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
-->
- 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 <n>` 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))
+1 -1
View File
@@ -97,7 +97,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
<!-- MOVED THIS TO v1.17
- [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)).
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fw-lateral-longitudinal-setpoint) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)).
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md).
-->
+3 -3
View File
@@ -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): <Badge type="warning" text="MC only" /> Smooth position and (optionally) heading control
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="warning" text="FW only" /> <Badge type="tip" text="PX4 v1.17" /> Direct control of lateral and longitudinal fixed wing dynamics
- [FwLateralLongitudinalSetpointType](#fw-lateral-longitudinal-setpoint): <Badge type="warning" text="FW only" /> <Badge type="tip" text="PX4 v1.17" /> 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): <Badge type="tip" text="PX4 v1.17" /> 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}
<Badge type="warning" text="Fixed wing only" /> <Badge type="tip" text="PX4 v1.17" />
@@ -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.
File diff suppressed because one or more lines are too long
Binary file not shown.
File diff suppressed because one or more lines are too long
@@ -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 <andreas@uaventure.com>
#
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)
@@ -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 <andreas@uaventure.com>
#
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)
@@ -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 <padr@kth.se>
#
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)
@@ -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("========================")
@@ -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 <andreas@uaventure.com>
#
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)

Some files were not shown because too many files have changed in this diff Show More