mirror of https://github.com/ArduPilot/ardupilot
Tools: ROS 2 update tests for time messages
Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
fd775bf08d
commit
628473c42e
|
@ -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 /ap/clock."""
|
||||
"""Subscribe to Time messages on topic /ap/time."""
|
||||
import rclpy
|
||||
import time
|
||||
|
||||
|
@ -22,14 +22,14 @@ from builtin_interfaces.msg import Time
|
|||
|
||||
|
||||
class TimeListener(Node):
|
||||
"""Subscribe to Time messages on topic /ap/clock."""
|
||||
"""Subscribe to Time messages on topic /ap/time."""
|
||||
|
||||
def __init__(self):
|
||||
"""Initialise the node."""
|
||||
super().__init__("time_listener")
|
||||
|
||||
# Declare and acquire `topic` parameter.
|
||||
self.declare_parameter("topic", "ap/clock")
|
||||
self.declare_parameter("topic", "ap/time")
|
||||
self.topic = self.get_parameter("topic").get_parameter_value().string_value
|
||||
|
||||
# Subscriptions.
|
||||
|
|
|
@ -28,7 +28,7 @@ from builtin_interfaces.msg import Time
|
|||
|
||||
|
||||
class TimeListener(rclpy.node.Node):
|
||||
"""Subscribe to Time messages on /ap/clock."""
|
||||
"""Subscribe to Time messages on /ap/time."""
|
||||
|
||||
def __init__(self):
|
||||
"""Initialise the node."""
|
||||
|
@ -36,7 +36,7 @@ class TimeListener(rclpy.node.Node):
|
|||
self.msg_event_object = threading.Event()
|
||||
|
||||
# Declare and acquire `topic` parameter.
|
||||
self.declare_parameter("topic", "ap/clock")
|
||||
self.declare_parameter("topic", "ap/time")
|
||||
self.topic = self.get_parameter("topic").get_parameter_value().string_value
|
||||
|
||||
def start_subscriber(self):
|
||||
|
@ -94,8 +94,8 @@ def launch_sitl_copter_dds_udp(sitl_copter_dds_udp):
|
|||
|
||||
|
||||
@pytest.mark.launch(fixture=launch_sitl_copter_dds_serial)
|
||||
def test_dds_serial_clock_msg_recv(launch_context, launch_sitl_copter_dds_serial):
|
||||
"""Test /ap/clock is published by AP_DDS."""
|
||||
def test_dds_serial_time_msg_recv(launch_context, launch_sitl_copter_dds_serial):
|
||||
"""Test /ap/time is published by AP_DDS."""
|
||||
_, actions = launch_sitl_copter_dds_serial
|
||||
virtual_ports = actions["virtual_ports"].action
|
||||
micro_ros_agent = actions["micro_ros_agent"].action
|
||||
|
@ -120,8 +120,8 @@ def test_dds_serial_clock_msg_recv(launch_context, launch_sitl_copter_dds_serial
|
|||
|
||||
|
||||
@pytest.mark.launch(fixture=launch_sitl_copter_dds_udp)
|
||||
def test_dds_udp_clock_msg_recv(launch_context, launch_sitl_copter_dds_udp):
|
||||
"""Test /ap/clock is published by AP_DDS."""
|
||||
def test_dds_udp_time_msg_recv(launch_context, launch_sitl_copter_dds_udp):
|
||||
"""Test /ap/time is published by AP_DDS."""
|
||||
_, actions = launch_sitl_copter_dds_udp
|
||||
micro_ros_agent = actions["micro_ros_agent"].action
|
||||
mavproxy = actions["mavproxy"].action
|
||||
|
|
Loading…
Reference in New Issue