ardupilot/libraries/AP_DDS/dds_xrce_profile.xml
Ryan Friedman 863656b037 AP_DDS: Add multi-topic support with NavSatFix
* Implement NavSatFix message
* Support covariance
* Set frame ID to WGS-84
* Closes #23284

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-03-30 13:41:28 +11:00

59 lines
1.5 KiB
XML

<?xml version="1.0"?>
<profiles>
<participant profile_name="participant_profile">
<rtps>
<name>Ardupilot_DDS_XRCE_Client</name>
</rtps>
</participant>
<topic profile_name="time__t">
<name>rt/ROS2_Time</name>
<dataType>builtin_interfaces::msg::dds_::Time_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>20</depth>
</historyQos>
</topic>
<data_writer profile_name="time__dw">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
<qos>
<reliability>
<kind>RELIABLE</kind>
</reliability>
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/ROS2_Time</name>
<dataType>builtin_interfaces::msg::dds_::Time_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>20</depth>
</historyQos>
</topic>
</data_writer>
<topic profile_name="navsatfix0__t">
<name>rt/ROS2_NavSatFix0</name>
<dataType>sensor_msgs::msg::dds_::NavSatFix_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>20</depth>
</historyQos>
</topic>
<data_writer profile_name="navsatfix0__dw">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
<qos>
<reliability>
<kind>RELIABLE</kind>
</reliability>
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/ROS2_NavSatFix0</name>
<dataType>sensor_msgs::msg::dds_::NavSatFix_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>20</depth>
</historyQos>
</topic>
</data_writer>
</profiles>