diff --git a/Tools/ros2/ardupilot_dds_tests/package.xml b/Tools/ros2/ardupilot_dds_tests/package.xml index 491021016a..c3eb345058 100644 --- a/Tools/ros2/ardupilot_dds_tests/package.xml +++ b/Tools/ros2/ardupilot_dds_tests/package.xml @@ -37,8 +37,7 @@ python3-pytest rclpy sensor_msgs - python-scipy - + python3-scipy ament_python diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_geopose_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_geopose_msg_received.py index 93e750b01e..64bb0329bd 100644 --- a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_geopose_msg_received.py +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_geopose_msg_received.py @@ -49,7 +49,7 @@ def ros_quat_to_heading(quat): def validate_position_cmac(position): - """Returns true if the vehicle is at CMAC""" + """Return true if the vehicle is at CMAC.""" LAT_LON_TOL = 1e-5 return ( math.isclose(position.latitude, CMAC_LAT, abs_tol=LAT_LON_TOL) @@ -59,12 +59,12 @@ def validate_position_cmac(position): def validate_heading_cmac(orientation): - """Returns true if the vehicle is facing the right way for CMAC""" + """Return true if the vehicle is facing the right way for CMAC.""" return math.isclose(ros_quat_to_heading(orientation), CMAC_HEADING) class GeoPoseListener(rclpy.node.Node): - """Subscribe to GeoPoseStamped messages""" + """Subscribe to GeoPoseStamped messages.""" def __init__(self): """Initialise the node."""