Skip to content

Commit bfbf3b6

Browse files
committed
Add ouster and velodyne tests
1 parent 8056e3b commit bfbf3b6

File tree

4 files changed

+118
-13
lines changed

4 files changed

+118
-13
lines changed

ros2_ws/src/rcdt_sensors/launch/ouster.launch.py

Lines changed: 3 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
from launch import LaunchContext, LaunchDescription
77
from launch.actions import OpaqueFunction
88
from launch_ros.actions import Node
9-
from rcdt_utilities.launch_utils import SKIP, LaunchArgument, get_file_path
9+
from rcdt_utilities.launch_utils import LaunchArgument
1010
from rcdt_utilities.register import Register
1111

1212
use_sim_arg = LaunchArgument("simulation", True, [True, False])
@@ -15,24 +15,18 @@
1515

1616

1717
def launch_setup(context: LaunchContext) -> list:
18-
"""Setup the launch description for the realsense camera.
18+
"""Setup the launch description for the Ouster lidar.
1919
2020
Args:
2121
context (LaunchContext): The launch context.
2222
2323
Returns:
2424
list: A list of actions to be executed.
2525
"""
26-
use_sim = use_sim_arg.bool_value(context)
26+
# Simulation-only setup
2727
namespace = namespace_arg.string_value(context)
2828
target_frame = target_frame_arg.string_value(context)
2929

30-
frame_prefix = namespace + "/" if namespace else ""
31-
32-
ouster_driver_node = None # Insert Ouster driver node
33-
34-
ouster_transform_node = None # Insert Ouster transform pointcloud node
35-
3630
pointcloud_to_laserscan_node = Node(
3731
package="pointcloud_to_laserscan",
3832
executable="pointcloud_to_laserscan_node",
@@ -53,8 +47,6 @@ def launch_setup(context: LaunchContext) -> list:
5347
)
5448

5549
return [
56-
# Register.on_start(ouster_driver_node, context) if not use_sim else SKIP,
57-
# Register.on_start(ouster_transform_node, context) if not use_sim else SKIP,
5850
Register.on_start(pointcloud_to_laserscan_node, context),
5951
]
6052

ros2_ws/src/rcdt_sensors/urdf/rcdt_os1_128.urdf.xacro

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,7 @@ SPDX-License-Identifier: Apache-2.0
77

88
<!--
99
Based on:
10-
1....
11-
2....
10+
1. https://data.ouster.io/downloads/datasheets/datasheet-rev7p1-os1.pdf
1211
-->
1312

1413
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="OS1-128">
Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
# SPDX-FileCopyrightText: Alliander N. V.
2+
#
3+
# SPDX-License-Identifier: Apache-2.0
4+
5+
6+
import launch_pytest
7+
import pytest
8+
from _pytest.fixtures import SubRequest
9+
from launch import LaunchDescription
10+
from rcdt_launch.robot import Lidar
11+
from rcdt_utilities.launch_utils import assert_for_message, get_file_path
12+
from rcdt_utilities.register import Register, RegisteredLaunchDescription
13+
from rcdt_utilities.test_utils import wait_for_register
14+
from sensor_msgs.msg import PointCloud2
15+
16+
namespace = "ouster"
17+
18+
19+
@launch_pytest.fixture(scope="module")
20+
def launch(request: SubRequest) -> LaunchDescription:
21+
"""Fixture to create launch file for the ouster test.
22+
23+
Args:
24+
request (SubRequest): The pytest request object, used to access command line options
25+
26+
Returns:
27+
LaunchDescription: The launch description for the ouster test.
28+
"""
29+
Lidar(platform="ouster", position=[0, 0, 0.5], namespace=namespace)
30+
launch = RegisteredLaunchDescription(
31+
get_file_path("rcdt_launch", ["launch"], "robots.launch.py"),
32+
launch_arguments={
33+
"rviz": "False",
34+
"simulation": request.config.getoption("simulation"),
35+
},
36+
)
37+
return Register.connect_context([launch])
38+
39+
40+
@pytest.mark.launch(fixture=launch)
41+
def test_wait_for_register(timeout: int) -> None:
42+
"""Test that the robot is registered in the system to start the tests.
43+
44+
Args:
45+
timeout (int): The timeout in seconds before stopping the test.
46+
"""
47+
wait_for_register(timeout=timeout)
48+
49+
50+
@pytest.mark.launch(fixture=launch)
51+
def test_points_published(timeout: int) -> None:
52+
"""Test that the pointcloud is published.
53+
54+
Args:
55+
timeout (int): The timeout in seconds to wait for the points to be published.
56+
"""
57+
assert_for_message(PointCloud2, f"/{namespace}/scan/points", timeout=timeout)
Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
# SPDX-FileCopyrightText: Alliander N. V.
2+
#
3+
# SPDX-License-Identifier: Apache-2.0
4+
5+
6+
import launch_pytest
7+
import pytest
8+
from _pytest.fixtures import SubRequest
9+
from launch import LaunchDescription
10+
from rcdt_launch.robot import Lidar
11+
from rcdt_utilities.launch_utils import assert_for_message, get_file_path
12+
from rcdt_utilities.register import Register, RegisteredLaunchDescription
13+
from rcdt_utilities.test_utils import wait_for_register
14+
from sensor_msgs.msg import PointCloud2
15+
16+
namespace = "velodyne"
17+
18+
19+
@launch_pytest.fixture(scope="module")
20+
def launch(request: SubRequest) -> LaunchDescription:
21+
"""Fixture to create launch file for the velodyne test.
22+
23+
Args:
24+
request (SubRequest): The pytest request object, used to access command line options
25+
26+
Returns:
27+
LaunchDescription: The launch description for the velodyne test.
28+
"""
29+
Lidar(platform="velodyne", position=[0, 0, 0.5], namespace=namespace)
30+
launch = RegisteredLaunchDescription(
31+
get_file_path("rcdt_launch", ["launch"], "robots.launch.py"),
32+
launch_arguments={
33+
"rviz": "False",
34+
"simulation": request.config.getoption("simulation"),
35+
},
36+
)
37+
return Register.connect_context([launch])
38+
39+
40+
@pytest.mark.launch(fixture=launch)
41+
def test_wait_for_register(timeout: int) -> None:
42+
"""Test that the robot is registered in the system to start the tests.
43+
44+
Args:
45+
timeout (int): The timeout in seconds before stopping the test.
46+
"""
47+
wait_for_register(timeout=timeout)
48+
49+
50+
@pytest.mark.launch(fixture=launch)
51+
def test_points_published(timeout: int) -> None:
52+
"""Test that the pointcloud is published.
53+
54+
Args:
55+
timeout (int): The timeout in seconds to wait for the points to be published.
56+
"""
57+
assert_for_message(PointCloud2, f"/{namespace}/scan/points", timeout=timeout)

0 commit comments

Comments
 (0)