Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
Add ouster and velodyne tests
  • Loading branch information
rosalievanark committed Oct 24, 2025
commit bfbf3b6da3073e9b5990f613d71af3af0773c1ba
14 changes: 3 additions & 11 deletions ros2_ws/src/rcdt_sensors/launch/ouster.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
from launch import LaunchContext, LaunchDescription
from launch.actions import OpaqueFunction
from launch_ros.actions import Node
from rcdt_utilities.launch_utils import SKIP, LaunchArgument, get_file_path
from rcdt_utilities.launch_utils import LaunchArgument
from rcdt_utilities.register import Register

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


def launch_setup(context: LaunchContext) -> list:
"""Setup the launch description for the realsense camera.
"""Setup the launch description for the Ouster lidar.

Args:
context (LaunchContext): The launch context.

Returns:
list: A list of actions to be executed.
"""
use_sim = use_sim_arg.bool_value(context)
# Simulation-only setup
namespace = namespace_arg.string_value(context)
target_frame = target_frame_arg.string_value(context)

frame_prefix = namespace + "/" if namespace else ""

ouster_driver_node = None # Insert Ouster driver node

ouster_transform_node = None # Insert Ouster transform pointcloud node

pointcloud_to_laserscan_node = Node(
package="pointcloud_to_laserscan",
executable="pointcloud_to_laserscan_node",
Expand All @@ -53,8 +47,6 @@ def launch_setup(context: LaunchContext) -> list:
)

return [
# Register.on_start(ouster_driver_node, context) if not use_sim else SKIP,
# Register.on_start(ouster_transform_node, context) if not use_sim else SKIP,
Register.on_start(pointcloud_to_laserscan_node, context),
]

Expand Down
3 changes: 1 addition & 2 deletions ros2_ws/src/rcdt_sensors/urdf/rcdt_os1_128.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,7 @@ SPDX-License-Identifier: Apache-2.0

<!--
Based on:
1....
2....
1. https://data.ouster.io/downloads/datasheets/datasheet-rev7p1-os1.pdf
-->

<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="OS1-128">
Expand Down
57 changes: 57 additions & 0 deletions ros2_ws/src/rcdt_test/rcdt_test/sensors/integration/test_ouster.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
# SPDX-FileCopyrightText: Alliander N. V.
#
# SPDX-License-Identifier: Apache-2.0


import launch_pytest
import pytest
from _pytest.fixtures import SubRequest
from launch import LaunchDescription
from rcdt_launch.robot import Lidar
from rcdt_utilities.launch_utils import assert_for_message, get_file_path
from rcdt_utilities.register import Register, RegisteredLaunchDescription
from rcdt_utilities.test_utils import wait_for_register
from sensor_msgs.msg import PointCloud2

namespace = "ouster"


@launch_pytest.fixture(scope="module")
def launch(request: SubRequest) -> LaunchDescription:
"""Fixture to create launch file for the ouster test.

Args:
request (SubRequest): The pytest request object, used to access command line options

Returns:
LaunchDescription: The launch description for the ouster test.
"""
Lidar(platform="ouster", position=[0, 0, 0.5], namespace=namespace)
launch = RegisteredLaunchDescription(
get_file_path("rcdt_launch", ["launch"], "robots.launch.py"),
launch_arguments={
"rviz": "False",
"simulation": request.config.getoption("simulation"),
},
)
return Register.connect_context([launch])


@pytest.mark.launch(fixture=launch)
def test_wait_for_register(timeout: int) -> None:
"""Test that the robot is registered in the system to start the tests.

Args:
timeout (int): The timeout in seconds before stopping the test.
"""
wait_for_register(timeout=timeout)


@pytest.mark.launch(fixture=launch)
def test_points_published(timeout: int) -> None:
"""Test that the pointcloud is published.

Args:
timeout (int): The timeout in seconds to wait for the points to be published.
"""
assert_for_message(PointCloud2, f"/{namespace}/scan/points", timeout=timeout)
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
# SPDX-FileCopyrightText: Alliander N. V.
#
# SPDX-License-Identifier: Apache-2.0


import launch_pytest
import pytest
from _pytest.fixtures import SubRequest
from launch import LaunchDescription
from rcdt_launch.robot import Lidar
from rcdt_utilities.launch_utils import assert_for_message, get_file_path
from rcdt_utilities.register import Register, RegisteredLaunchDescription
from rcdt_utilities.test_utils import wait_for_register
from sensor_msgs.msg import PointCloud2

namespace = "velodyne"


@launch_pytest.fixture(scope="module")
def launch(request: SubRequest) -> LaunchDescription:
"""Fixture to create launch file for the velodyne test.

Args:
request (SubRequest): The pytest request object, used to access command line options

Returns:
LaunchDescription: The launch description for the velodyne test.
"""
Lidar(platform="velodyne", position=[0, 0, 0.5], namespace=namespace)
launch = RegisteredLaunchDescription(
get_file_path("rcdt_launch", ["launch"], "robots.launch.py"),
launch_arguments={
"rviz": "False",
"simulation": request.config.getoption("simulation"),
},
)
return Register.connect_context([launch])


@pytest.mark.launch(fixture=launch)
def test_wait_for_register(timeout: int) -> None:
"""Test that the robot is registered in the system to start the tests.

Args:
timeout (int): The timeout in seconds before stopping the test.
"""
wait_for_register(timeout=timeout)


@pytest.mark.launch(fixture=launch)
def test_points_published(timeout: int) -> None:
"""Test that the pointcloud is published.

Args:
timeout (int): The timeout in seconds to wait for the points to be published.
"""
assert_for_message(PointCloud2, f"/{namespace}/scan/points", timeout=timeout)
Loading