Skip to content

Commit

Permalink
Merge branch 'release/1.15' into v1.15/jazzy
Browse files Browse the repository at this point in the history
  • Loading branch information
MDEAGEWT committed Feb 6, 2025
2 parents 6504484 + 18cbcce commit b1b2e58
Show file tree
Hide file tree
Showing 68 changed files with 565 additions and 127 deletions.
39 changes: 25 additions & 14 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -3,27 +3,38 @@ name: Build package
# CI runs over all branches that do not contain 'ros1' in the name
on:
push:
branches:
- 'main'
schedule:
- cron: '0 0 * * *'

defaults:
run:
shell: bash

jobs:
build:
name: "Build"
focal:
name: "Build on Ubuntu Focal"
runs-on: ubuntu-20.04
container: px4io/px4-dev-ros2-${{ matrix.ros2_distro }}:2021-05-31
steps:
- uses: actions/checkout@v4
- uses: ros-tooling/[email protected]
with:
required-ros-distributions: foxy
- uses: ros-tooling/[email protected]
with:
package-name: px4_msgs
target-ros2-distro: foxy
jammy:
name: "Build on Ubuntu Jammy"
runs-on: ubuntu-22.04
strategy:
matrix:
ros2_distro: [foxy, humble, rolling]
ros2_distro: [humble, rolling]
steps:
- uses: actions/checkout@v3
- name: build
run: |
source /opt/ros/${{ matrix.ros2_distro }}/setup.bash
mkdir -p ~/colcon_ws/src
cd ~/colcon_ws
ln -s ${GITHUB_WORKSPACE} src/px4_msgs
colcon build --cmake-args --symlink-install --event-handlers console_direct+
- uses: actions/checkout@v4
- uses: ros-tooling/[email protected]
with:
required-ros-distributions: ${{ matrix.ros2_distro }}
- uses: ros-tooling/[email protected]
with:
package-name: px4_msgs
target-ros2-distro: ${{ matrix.ros2_distro }}
10 changes: 6 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,14 @@ find_package(rosidl_default_generators REQUIRED)
set(MSGS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/msg")
file(GLOB PX4_MSGS RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" "${MSGS_DIR}/*.msg")

file(GLOB ROS_MSG_DIR_LIST "${MSGS_DIR}/*.msg")

set(ROS_MSG_DIR_LIST "${ROS_MSG_DIR_LIST}" CACHE INTERNAL "ROS_MSG_DIR_LIST")
# get all srv files
set(SRVS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/srv")
file(GLOB PX4_SRVS RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" "${SRVS_DIR}/*.srv")

# Generate introspection typesupport for C and C++ and IDL files
rosidl_generate_interfaces(${PROJECT_NAME} ${PX4_MSGS}
rosidl_generate_interfaces(${PROJECT_NAME}
${PX4_MSGS}
${PX4_SRVS}
DEPENDENCIES builtin_interfaces
ADD_LINTER_TESTS
)
Expand Down
45 changes: 37 additions & 8 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,25 +2,54 @@

[![GitHub license](https://img.shields.io/github/license/PX4/px4_msgs.svg)](https://github.com/PX4/px4_msg/blob/master/LICENSE) [![Build package](https://github.com/PX4/px4_msgs/workflows/Build%20package/badge.svg)](https://github.com/PX4/px4_msgs/actions)

This package contains the ROS2 message definitions of the [PX4 Pro ecosystem](https://px4.io/). Building this package generates all the required interfaces to interface ROS2 nodes with the PX4 autopilot internals, which use the [uORB messaging API](https://dev.px4.io/en/middleware/uorb.html). Currently the messages of this package represent a dependency to [`px4_ros_com` package](https://github.com/PX4/px4_ros_com).
[![Discord Shield](https://discordapp.com/api/guilds/1022170275984457759/widget.png?style=shield)](https://discord.gg/dronecode)

## uORB message definitions
ROS 2 message definitions for the [PX4 Autopilot](https://px4.io/) project.

The uORB message definitions, which represent the counter-part of the ROS2 messages found in this package, can be found on the [PX4 Firmware repository](https://github.com/PX4/Firmware).
Building this package generates all the required interfaces to interface ROS 2 nodes with the PX4 internals.

## How are these messsage definitions generated?
## Supported versions and compatibility

When uORB message definitions in the [PX4 firmware](https://github.com/PX4/Firmware) repository change, a CI/CD pipeline automatically generates and pushes updated ROS message definitions to this repository. The ROS message definitions are generated by the [`uorb_to_ros_msgs.py`](https://github.com/PX4/Firmware/blob/master/msg/tools/uorb_to_ros_msgs.py) script. One can also use this script to generate its own ROS message definitions for new or modified uORB messages.
Depending on the PX4 and ROS versions you want to use, you need to checkout the appropriate branch of this package:

| PX4 | ROS 2 | Ubuntu | branch |
|----------------|---------|--------------|-------------------------------------------------------------------|
| [v1.13](https://github.com/PX4/px4_msgs/tree/release/1.13) | Foxy | Ubuntu 20.04 | [release/1.13](https://github.com/PX4/px4_msgs/tree/release/1.13) |
| [v1.14](https://github.com/PX4/px4_msgs/tree/release/1.14) | Foxy | Ubuntu 20.04 | [release/1.14](https://github.com/PX4/px4_msgs/tree/release/1.14) |
| [v1.14](https://github.com/PX4/px4_msgs/tree/release/1.14) | Humble | Ubuntu 22.04 | [release/1.14](https://github.com/PX4/px4_msgs/tree/release/1.14) |
| [v1.14](https://github.com/PX4/px4_msgs/tree/release/1.14) | Rolling | Ubuntu 22.04 | [release/1.14](https://github.com/PX4/px4_msgs/tree/release/1.14) |
| [v1.15](https://github.com/PX4/px4_msgs/tree/release/1.15) | Foxy | Ubuntu 20.04 | [release/1.15](https://github.com/PX4/px4_msgs/tree/release/1.15) |
| [v1.15](https://github.com/PX4/px4_msgs/tree/release/1.15) | Humble | Ubuntu 22.04 | [release/1.15](https://github.com/PX4/px4_msgs/tree/release/1.15) |
| [v1.15](https://github.com/PX4/px4_msgs/tree/release/1.15) | Rolling | Ubuntu 22.04 | [release/1.15](https://github.com/PX4/px4_msgs/tree/release/1.15) |
| [main](https://github.com/PX4/px4_msgs/tree/main) | Foxy | Ubuntu 22.04 | [main](https://github.com/PX4/px4_msgs) |
| [main](https://github.com/PX4/px4_msgs/tree/main) | Humble | Ubuntu 22.04 | [main](https://github.com/PX4/px4_msgs) |
| [main](https://github.com/PX4/px4_msgs/tree/main) | Rolling | Ubuntu 22.04 | [main](https://github.com/PX4/px4_msgs) |

### Messages Sync from PX4

When PX4 message definitions in the `main` branch of [PX4 Autopilot](https://github.com/PX4/PX4-Autopilot) change, a [CI/CD pipeline](https://github.com/PX4/PX4-Autopilot/blob/main/.github/workflows/metadata.yml#L119) automatically copies and pushes updated ROS message definitions to this repository. This ensures that this repository `main` branch and the PX4-Autopilot `main` branch are always up to date.
However, if you are using a custom PX4 version and you modified existing messages or created new one, then you have to manually synchronize them in this repository:
### Manual Message Sync

- Checkout the correct branch associated to the PX4 version from which you detached you custom version.
- Delete all `*.msg` and `*.srv` files in `msg/` and `srv/`.
- Copy all `*.msg` and `*.srv` files from `PX4-Autopilot/msg/` and `PX4-Autopilot/srv/` in `msg/` and `srv/`, respectively. Assuming that this repository and the PX4-Autopilot repository are placed in your home folder, you can run:
```sh
rm -f ~/px4_msgs/msg/*.msg
rm -f ~/px4_msgs/srv/*.srv
cp ~/PX4-Autopilot/msg/*.msg ~/px4_msgs/msg/
cp ~/PX4-Autopilot/srv/*.srv ~/px4_msgs/srv/
```

## Install, build and usage

Check the [`Ament` tutorial](https://index.ros.org/doc/ros2/Tutorials/Ament-Tutorial/) to understand how this can be built inside a worspace. Check the [RTPS/ROS2 Interface](https://dev.px4.io/en/middleware/micrortps.html) section on the PX4 Devguide for further details on how this integrates with the [`px4_ros_com` package](https://github.com/PX4/px4_ros_com).
Check [Using colcon to build packages](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-Your-First-ROS2-Package.html#build-a-package) to understand how this can be built inside a workspace. Check the [PX4 ROS 2 User Guide](https://docs.px4.io/main/en/ros/ros2_comm.html) section on the PX4 documentation for further details on how this integrates PX4 and how to exchange messages with the autopilot.

## Bug tracking and feature requests

Use the [Issues](https://github.com/PX4/px4_msgs/issues) section to create a new issue. Report your issue or feature request [here](https://github.com/PX4/px4_msgs/issues/new).

## Questions and troubleshooting

Reach the PX4 development team on the `#messaging` PX4 Slack channel:
[![Slack](https://px4-slack.herokuapp.com/badge.svg)](http://slack.px4.io)
Reach the PX4 development team on the [PX4 Discord Server](https://discord.gg/dronecode).

2 changes: 1 addition & 1 deletion msg/ActuatorTest.msg
Original file line number Diff line number Diff line change
Expand Up @@ -18,4 +18,4 @@ float32 value # range: [-1, 1], where 1 means maximum positive output,
# and NaN maps to disarmed (stop the motors)
uint32 timeout_ms # timeout in ms after which to exit test mode (if 0, do not time out)

uint8 ORB_QUEUE_LENGTH = 12 # same as MAX_NUM_MOTORS to support code in esc_calibration
uint8 ORB_QUEUE_LENGTH = 16 # >= MAX_NUM_MOTORS to support code in esc_calibration
33 changes: 33 additions & 0 deletions msg/ArmingCheckReply.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
uint64 timestamp # time since system start (microseconds)

uint8 request_id
uint8 registration_id

uint8 HEALTH_COMPONENT_INDEX_NONE = 0
uint8 HEALTH_COMPONENT_INDEX_AVOIDANCE = 19

uint8 health_component_index # HEALTH_COMPONENT_INDEX_*
bool health_component_is_present
bool health_component_warning
bool health_component_error

bool can_arm_and_run # whether arming is possible, and if it's a navigation mode, if it can run

uint8 num_events

Event[5] events

# Mode requirements
bool mode_req_angular_velocity
bool mode_req_attitude
bool mode_req_local_alt
bool mode_req_local_position
bool mode_req_local_position_relaxed
bool mode_req_global_position
bool mode_req_mission
bool mode_req_home_position
bool mode_req_prevent_arming
bool mode_req_manual_control


uint8 ORB_QUEUE_LENGTH = 4
5 changes: 5 additions & 0 deletions msg/ArmingCheckRequest.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
uint64 timestamp # time since system start (microseconds)

# broadcast message to request all registered arming checks to be reported

uint8 request_id
2 changes: 1 addition & 1 deletion msg/BatteryStatus.msg
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ float32 voltage_v # Battery voltage in volts, 0 if unknown
float32 voltage_filtered_v # Battery voltage in volts, filtered, 0 if unknown
float32 current_a # Battery current in amperes, -1 if unknown
float32 current_filtered_a # Battery current in amperes, filtered, 0 if unknown
float32 current_average_a # Battery current average in amperes, -1 if unknown
float32 current_average_a # Battery current average in amperes (for FW average in level flight), -1 if unknown
float32 discharged_mah # Discharged amount in mAh, -1 if unknown
float32 remaining # From 1 to 0, -1 if unknown
float32 scale # Power scaling factor, >= 1, or -1 if unknown
Expand Down
9 changes: 9 additions & 0 deletions msg/Buffer128.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
uint64 timestamp # time since system start (microseconds)

uint8 len # length of data
uint32 MAX_BUFLEN = 128

uint8[128] data # data

# TOPICS voxl2_io_data

6 changes: 6 additions & 0 deletions msg/CanInterfaceStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
uint64 timestamp # time since system start (microseconds)
uint8 interface

uint64 io_errors
uint64 frames_tx
uint64 frames_rx
18 changes: 18 additions & 0 deletions msg/ConfigOverrides.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
# Configurable overrides by (external) modes or mode executors
uint64 timestamp # time since system start (microseconds)

bool disable_auto_disarm # Prevent the drone from automatically disarming after landing (if configured)

bool defer_failsafes # Defer all failsafes that can be deferred (until the flag is cleared)
int16 defer_failsafes_timeout_s # Maximum time a failsafe can be deferred. 0 = system default, -1 = no timeout


int8 SOURCE_TYPE_MODE = 0
int8 SOURCE_TYPE_MODE_EXECUTOR = 1
int8 source_type

uint8 source_id # ID depending on source_type

uint8 ORB_QUEUE_LENGTH = 4

# TOPICS config_overrides config_overrides_request
8 changes: 8 additions & 0 deletions msg/DatamanRequest.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
uint64 timestamp # time since system start (microseconds)

uint8 client_id
uint8 request_type # id/read/write/clear
uint8 item # dm_item_t
uint32 index
uint8[56] data
uint32 data_length
15 changes: 15 additions & 0 deletions msg/DatamanResponse.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
uint64 timestamp # time since system start (microseconds)

uint8 client_id
uint8 request_type # id/read/write/clear
uint8 item # dm_item_t
uint32 index
uint8[56] data

uint8 STATUS_SUCCESS = 0
uint8 STATUS_FAILURE_ID_ERR = 1
uint8 STATUS_FAILURE_NO_DATA = 2
uint8 STATUS_FAILURE_READ_FAILED = 3
uint8 STATUS_FAILURE_WRITE_FAILED = 4
uint8 STATUS_FAILURE_CLEAR_FAILED = 5
uint8 status
8 changes: 8 additions & 0 deletions msg/DifferentialDriveSetpoint.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
uint64 timestamp # time since system start (microseconds)

float32 speed # [m/s] collective roll-off speed in body x-axis
bool closed_loop_speed_control # true if speed is controlled using estimator feedback, false if direct feed-forward
float32 yaw_rate # [rad/s] yaw rate
bool closed_loop_yaw_rate_control # true if yaw rate is controlled using gyroscope feedback, false if direct feed-forward

# TOPICS differential_drive_setpoint differential_drive_control_output
4 changes: 2 additions & 2 deletions msg/EstimatorAidSource1d.msg
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,11 @@ float32 innovation
float32 innovation_variance
float32 test_ratio

bool fusion_enabled # true when measurements are being fused
bool innovation_rejected # true if the observation has been rejected
bool fused # true if the sample was successfully fused

# TOPICS estimator_aid_src_baro_hgt estimator_aid_src_ev_hgt estimator_aid_src_gnss_hgt estimator_aid_src_rng_hgt
# TOPICS estimator_aid_src_airspeed estimator_aid_src_sideslip
# TOPICS estimator_aid_src_fake_hgt
# TOPICS estimator_aid_src_mag_heading estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw
# TOPICS estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw
# TOPICS estimator_aid_src_terrain_range_finder
4 changes: 2 additions & 2 deletions msg/EstimatorAidSource2d.msg
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@ float32[2] innovation
float32[2] innovation_variance
float32[2] test_ratio

bool fusion_enabled # true when measurements are being fused
bool innovation_rejected # true if the observation has been rejected
bool fused # true if the sample was successfully fused

# TOPICS estimator_aid_src_ev_pos estimator_aid_src_fake_pos estimator_aid_src_gnss_pos
# TOPICS estimator_aid_src_ev_pos estimator_aid_src_fake_pos estimator_aid_src_gnss_pos estimator_aid_src_aux_global_position
# TOPICS estimator_aid_src_aux_vel estimator_aid_src_optical_flow estimator_aid_src_terrain_optical_flow
# TOPICS estimator_aid_src_drag
1 change: 0 additions & 1 deletion msg/EstimatorAidSource3d.msg
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@ float32[3] innovation
float32[3] innovation_variance
float32[3] test_ratio

bool fusion_enabled # true when measurements are being fused
bool innovation_rejected # true if the observation has been rejected
bool fused # true if the sample was successfully fused

Expand Down
1 change: 0 additions & 1 deletion msg/EstimatorInnovations.msg
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ float32 baro_vpos # barometer height innovation (m) and innovation variance (m**

# Auxiliary velocity
float32[2] aux_hvel # horizontal auxiliary velocity innovation from landing target measurement (m/sec) and innovation variance ((m/sec)**2)
float32 aux_vvel # vertical auxiliary velocity innovation from landing target measurement (m/sec) and innovation variance ((m/sec)**2)

# Optical flow
float32[2] flow # flow innvoation (rad/sec) and innovation variance ((rad/sec)**2)
Expand Down
2 changes: 1 addition & 1 deletion msg/EstimatorStates.msg
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,4 @@ uint64 timestamp_sample # the timestamp of the raw data (microseconds)
float32[24] states # Internal filter states
uint8 n_states # Number of states effectively used

float32[24] covariances # Diagonal Elements of Covariance Matrix
float32[23] covariances # Diagonal Elements of Covariance Matrix
5 changes: 5 additions & 0 deletions msg/EstimatorStatus.msg
Original file line number Diff line number Diff line change
Expand Up @@ -127,3 +127,8 @@ uint32 mag_device_id
# legacy local position estimator (LPE) flags
uint8 health_flags # Bitmask to indicate sensor health states (vel, pos, hgt)
uint8 timeout_flags # Bitmask to indicate timeout flags (vel, pos, hgt)

float32 mag_inclination_deg
float32 mag_inclination_ref_deg
float32 mag_strength_gs
float32 mag_strength_ref_gs
16 changes: 7 additions & 9 deletions msg/EstimatorStatusFlags.msg
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,10 @@ bool cs_rng_kin_consistent # 31 - true when the range finder kinematic cons
bool cs_fake_pos # 32 - true when fake position measurements are being fused
bool cs_fake_hgt # 33 - true when fake height measurements are being fused
bool cs_gravity_vector # 34 - true when gravity vector measurements are being fused
bool cs_mag # 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended
bool cs_ev_yaw_fault # 36 - true when the EV heading has been declared faulty and is no longer being used
bool cs_mag_heading_consistent # 37 - true when the heading obtained from mag data is declared consistent with the filter
bool cs_aux_gpos # 38 - true if auxiliary global position measurement fusion is intended

# fault status
uint32 fault_status_changes # number of filter fault status (fs) changes
Expand All @@ -51,15 +55,9 @@ bool fs_bad_airspeed # 5 - true if fusion of the airspeed has encounte
bool fs_bad_sideslip # 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error
bool fs_bad_optflow_x # 7 - true if fusion of the optical flow X axis has encountered a numerical error
bool fs_bad_optflow_y # 8 - true if fusion of the optical flow Y axis has encountered a numerical error
bool fs_bad_vel_n # 9 - true if fusion of the North velocity has encountered a numerical error
bool fs_bad_vel_e # 10 - true if fusion of the East velocity has encountered a numerical error
bool fs_bad_vel_d # 11 - true if fusion of the Down velocity has encountered a numerical error
bool fs_bad_pos_n # 12 - true if fusion of the North position has encountered a numerical error
bool fs_bad_pos_e # 13 - true if fusion of the East position has encountered a numerical error
bool fs_bad_pos_d # 14 - true if fusion of the Down position has encountered a numerical error
bool fs_bad_acc_bias # 15 - true if bad delta velocity bias estimates have been detected
bool fs_bad_acc_vertical # 16 - true if bad vertical accelerometer data has been detected
bool fs_bad_acc_clipping # 17 - true if delta velocity data contains clipping (asymmetric railing)
bool fs_bad_acc_bias # 9 - true if bad delta velocity bias estimates have been detected
bool fs_bad_acc_vertical # 10 - true if bad vertical accelerometer data has been detected
bool fs_bad_acc_clipping # 11 - true if delta velocity data contains clipping (asymmetric railing)


# innovation test failures
Expand Down
2 changes: 1 addition & 1 deletion msg/FailsafeFlags.msg
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ bool battery_low_remaining_time # Low battery based on remaining flight ti
bool battery_unhealthy # Battery unhealthy

# Other
bool primary_geofence_breached # Primary Geofence breached
bool geofence_breached # Geofence breached (one or multiple)
bool mission_failure # Mission failure
bool vtol_fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute)
bool wind_limit_exceeded # Wind limit exceeded
Expand Down
8 changes: 8 additions & 0 deletions msg/FigureEightStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
uint64 timestamp # time since system start (microseconds)
float32 major_radius # Major axis radius of the figure eight [m]. Positive values orbit clockwise, negative values orbit counter-clockwise.
float32 minor_radius # Minor axis radius of the figure eight [m].
float32 orientation # Orientation of the major axis of the figure eight [rad].
uint8 frame # The coordinate system of the fields: x, y, z.
int32 x # X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
int32 y # Y coordinate of center point. Coordinate system depends on frame field: local = y position in meters * 1e4, global = latitude in degrees * 1e7.
float32 z # Altitude of center point. Coordinate system depends on frame field.
8 changes: 8 additions & 0 deletions msg/FlightPhaseEstimation.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
uint64 timestamp # time since system start (microseconds)

uint8 flight_phase # Estimate of current flight phase

uint8 FLIGHT_PHASE_UNKNOWN = 0 # vehicle flight phase is unknown
uint8 FLIGHT_PHASE_LEVEL = 1 # Vehicle is in level flight
uint8 FLIGHT_PHASE_DESCEND = 2 # vehicle is in descend
uint8 FLIGHT_PHASE_CLIMB = 3 # vehicle is climbing
Loading

0 comments on commit b1b2e58

Please sign in to comment.