Skip to content

Multi-Vehicle Симуляція з ROS 2

XRCE-DDS allows for multiple clients to be connected to the same agent over UDP. Це особливо корисно в симуляції, якщо потрібно запустити лише один агент.

Налаштування та вимоги

Єдині вимоги

Принцип операції

In simulation each PX4 instance receives a unique px4_instance number starting from 0. This value is used to assign a unique value to UXRCE_DDS_KEY:

sh
param set UXRCE_DDS_KEY $((px4_instance+1))

INFO

By doing so, UXRCE_DDS_KEY will always coincide with MAV_SYS_ID.

Moreover, when px4_instance is greater than zero, a unique ROS 2 namespace prefix in the form px4_$px4_instance is added:

sh
uxrce_dds_ns="-n px4_$px4_instance"

INFO

The environment variable PX4_UXRCE_DDS_NS, if set, will override the namespace behavior described above.

The first instance (px4_instance=0) does not have an additional namespace in order to be consistent with the default behavior of the xrce-dds client on a real vehicle. This mismatch can be fixed by manually using PX4_UXRCE_DDS_NS on the first instance or by starting adding vehicles from index 1 instead of 0 (this is the default behavior adopted by sitl_multiple_run.sh for Gazebo Classic).

Типове налаштування клієнта у симуляції:

PX4_UXRCE_DDS_NSpx4_instanceUXRCE_DDS_KEYclient namespace
not provided0px4_instance+1нічого
provided0px4_instance+1PX4_UXRCE_DDS_NS
not provided> 0px4_instance+1px4_${px4_instance}
provided> 0px4_instance+1PX4_UXRCE_DDS_NS

Adjusting the target_system value

PX4 accepts VehicleCommand messages only if their target_system field is zero (broadcast communication) or coincides with MAV_SYS_ID. У всіх інших ситуаціях повідомлення ігноруються. Therefore, when ROS 2 nodes want to send VehicleCommand to PX4, they must ensure that the messages are filled with the appropriate target_system value.

For example, if you want to send a command to your third vehicle, which has px4_instance=2, you need to set target_system=3 in all your VehicleCommand messages.