Tools: update ROS 2 DDS topic names

Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
Rhys Mainwaring 2023-04-25 22:57:54 +01:00 committed by Andrew Tridgell
parent a654027a45
commit 09ee6b8651
3 changed files with 8 additions and 8 deletions

View File

@ -13,7 +13,7 @@
# You should have received a copy of the GNU General Public License
# along with this program. If not, see <https://www.gnu.org/licenses/>.
"""Subscribe to Time messages on topic /ROS2_Time."""
"""Subscribe to Time messages on topic /ap/clock."""
import rclpy
import time
@ -22,14 +22,14 @@ from builtin_interfaces.msg import Time
class TimeListener(Node):
"""Subscribe to Time messages on topic /ROS2_Time."""
"""Subscribe to Time messages on topic /ap/clock."""
def __init__(self):
"""Initialise the node."""
super().__init__("time_listener")
# Declare and acquire `topic` parameter.
self.declare_parameter("topic", "ROS2_Time")
self.declare_parameter("topic", "ap/clock")
self.topic = self.get_parameter("topic").get_parameter_value().string_value
# Subscriptions.

View File

@ -39,7 +39,7 @@ def launch_description(sitl_dds):
class NavSatFixListener(rclpy.node.Node):
"""Subscribe to NavSatFix messages on /ROS2_NavSatFix0."""
"""Subscribe to NavSatFix messages on /ap/navsat/navsat0."""
def __init__(self):
"""Initialise the node."""
@ -47,7 +47,7 @@ class NavSatFixListener(rclpy.node.Node):
self.msg_event_object = threading.Event()
# Declare and acquire `topic` parameter
self.declare_parameter("topic", "ROS2_NavSatFix0")
self.declare_parameter("topic", "ap/navsat/navsat0")
self.topic = self.get_parameter("topic").get_parameter_value().string_value
def start_subscriber(self):
@ -88,7 +88,7 @@ def test_navsat_msgs_received(sitl_dds, launch_context):
node = NavSatFixListener()
node.start_subscriber()
msgs_received_flag = node.msg_event_object.wait(timeout=10.0)
assert msgs_received_flag, "Did not receive 'ROS2_NavSatFix0' msgs."
assert msgs_received_flag, "Did not receive 'ap/navsat/navsat0' msgs."
finally:
rclpy.shutdown()

View File

@ -37,7 +37,7 @@ def launch_description(sitl_dds):
class TimeListener(rclpy.node.Node):
"""Subscribe to Time messages on /ROS2_Time."""
"""Subscribe to Time messages on /ap/clock."""
def __init__(self):
"""Initialise the node."""
@ -45,7 +45,7 @@ class TimeListener(rclpy.node.Node):
self.msg_event_object = threading.Event()
# Declare and acquire `topic` parameter.
self.declare_parameter("topic", "ROS2_Time")
self.declare_parameter("topic", "ap/clock")
self.topic = self.get_parameter("topic").get_parameter_value().string_value
def start_subscriber(self):