AP_DDS: update topic names

- Change to lower case and prefix with /ap

Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
Rhys Mainwaring 2023-04-21 21:40:34 +01:00 committed by Andrew Tridgell
parent 819431050a
commit a654027a45
2 changed files with 21 additions and 18 deletions

View File

@ -146,19 +146,22 @@ After your setups are complete, do the following:
$ ros2 topic list -v
Published topics:
* /ROS2_NavSatFix0 [sensor_msgs/msg/NavSatFix] 1 publisher
* /ROS2_Time [builtin_interfaces/msg/Time] 1 publisher
* /parameter_events [rcl_interfaces/msg/ParameterEvent] 1 publisher
* /rosout [rcl_interfaces/msg/Log] 1 publisher
* /tf [tf2_msgs/msg/TFMessage] 1 publisher
* /ap/battery/battery0 [sensor_msgs/msg/BatteryState] 1 publisher
* /ap/clock [builtin_interfaces/msg/Time] 1 publisher
* /ap/navsat/navsat0 [sensor_msgs/msg/NavSatFix] 1 publisher
* /ap/pose/filtered [geometry_msgs/msg/PoseStamped] 1 publisher
* /ap/tf_static [tf2_msgs/msg/TFMessage] 1 publisher
* /parameter_events [rcl_interfaces/msg/ParameterEvent] 1 publisher
* /rosout [rcl_interfaces/msg/Log] 1 publisher
Subscribed topics:
$ ros2 topic hz /ROS2_Time
$ ros2 topic hz /ap/clock
average rate: 50.115
min: 0.012s max: 0.024s std dev: 0.00328s window: 52
$ ros2 topic echo /ROS2_Time
$ ros2 topic echo /ap/clock
sec: 1678668735
nanosec: 729410000
---
@ -166,7 +169,7 @@ After your setups are complete, do the following:
The static transforms for enabled sensors are also published, and can be recieved like so:
```console
ros2 topic echo /tf --qos-depth 1 --qos-history keep_last --qos-reliability reliable --qos-durability transient_local --once
ros2 topic echo /ap/tf_static --qos-depth 1 --qos-history keep_last --qos-reliability reliable --qos-durability transient_local --once
```
In order to consume the transforms, it's highly recommended to [create and run a transform broadcaster in ROS 2](https://docs.ros.org/en/humble/Concepts/About-Tf2.html#tutorials).

View File

@ -6,7 +6,7 @@
</rtps>
</participant>
<topic profile_name="time__t">
<name>rt/ROS2_Time</name>
<name>rt/ap/clock</name>
<dataType>builtin_interfaces::msg::dds_::Time_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
@ -22,7 +22,7 @@
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/ROS2_Time</name>
<name>rt/ap/clock</name>
<dataType>builtin_interfaces::msg::dds_::Time_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
@ -31,7 +31,7 @@
</topic>
</data_writer>
<topic profile_name="navsatfix0__t">
<name>rt/ROS2_NavSatFix0</name>
<name>rt/ap/navsat/navsat0</name>
<dataType>sensor_msgs::msg::dds_::NavSatFix_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
@ -50,7 +50,7 @@
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/ROS2_NavSatFix0</name>
<name>rt/ap/navsat/navsat0</name>
<dataType>sensor_msgs::msg::dds_::NavSatFix_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
@ -59,7 +59,7 @@
</topic>
</data_writer>
<topic profile_name="statictransforms__t">
<name>rt/tf</name>
<name>rt/ap/tf_static</name>
<dataType>tf2_msgs::msg::dds_::TFMessage_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
@ -78,7 +78,7 @@
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/tf</name>
<name>rt/ap/tf_static</name>
<dataType>tf2_msgs::msg::dds_::TFMessage_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
@ -87,7 +87,7 @@
</topic>
</data_writer>
<topic profile_name="batterystate0__t">
<name>rt/ROS2_BatteryState0</name>
<name>rt/ap/battery/battery0</name>
<dataType>sensor_msgs::msg::dds_::BatteryState_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
@ -106,7 +106,7 @@
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/ROS2_BatteryState0</name>
<name>rt/ap/battery/battery0</name>
<dataType>sensor_msgs::msg::dds_::BatteryState_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
@ -115,7 +115,7 @@
</topic>
</data_writer>
<topic profile_name="localpose__t">
<name>rt/ROS2_LocalPose</name>
<name>rt/ap/pose/filtered</name>
<dataType>geometry_msgs::msg::dds_::PoseStamped_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
@ -134,7 +134,7 @@
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/ROS2_LocalPose</name>
<name>rt/ap/pose/filtered</name>
<dataType>geometry_msgs::msg::dds_::PoseStamped_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>