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
Ouster Lidar works in simulation, nr of channels lowered since the si…
…mulation could not handle 128 channels ('Extrapolation Error looking up target frame')
  • Loading branch information
rosalievanark committed Oct 23, 2025
commit a4f47566a430745db99a01e0bd495488a5c843e8
37 changes: 26 additions & 11 deletions ros2_ws/src/rcdt_launch/rcdt_launch/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,16 @@ def order_platforms() -> None:
Raises:
ValueError: If an unknown platform is encountered.
"""
order = ["panther", "franka", "velodyne", "ouster", "realsense", "zed", "nmea", "axis"]
order = [
"panther",
"franka",
"velodyne",
"ouster",
"realsense",
"zed",
"nmea",
"axis",
]

for platform in Platform.platforms:
if platform.platform not in order:
Expand Down Expand Up @@ -296,7 +305,14 @@ def create_map_links() -> list[Node]:
def __init__( # noqa: PLR0913
self,
platform: Literal[
"panther", "franka", "velodyne", "ouster", "realsense", "zed", "nmea", "axis"
"panther",
"franka",
"velodyne",
"ouster",
"realsense",
"zed",
"nmea",
"axis",
],
position: list,
orientation: list | None = None,
Expand Down Expand Up @@ -766,15 +782,14 @@ def create_ouster_launch(self) -> RegisteredLaunchDescription:
else:
target_frame = f"{self.namespace}/base_link"

# return RegisteredLaunchDescription(
# get_file_path("rcdt_sensors", ["launch"], "ouster.launch.py"),
# launch_arguments={
# "simulation": str(Platform.simulation),
# "namespace": self.namespace,
# "target_frame": target_frame,
# },
# )
pass # TODO: create/adjust commented launch file
return RegisteredLaunchDescription(
get_file_path("rcdt_sensors", ["launch"], "ouster.launch.py"),
launch_arguments={
"simulation": str(Platform.simulation),
"namespace": self.namespace,
"target_frame": target_frame,
},
)


class Arm(Platform):
Expand Down
74 changes: 74 additions & 0 deletions ros2_ws/src/rcdt_sensors/launch/ouster.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
# SPDX-FileCopyrightText: Alliander N. V.
#
# SPDX-License-Identifier: Apache-2.0


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.register import Register

use_sim_arg = LaunchArgument("simulation", True, [True, False])
namespace_arg = LaunchArgument("namespace", "ouster")
target_frame_arg = LaunchArgument("target_frame", "")


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

Args:
context (LaunchContext): The launch context.

Returns:
list: A list of actions to be executed.
"""
use_sim = use_sim_arg.bool_value(context)
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",
remappings=[
("cloud_in", f"/{namespace}/scan/points"),
("scan", f"/{namespace}/scan"),
],
parameters=[
{
"target_frame": target_frame,
"min_height": 0.1,
"max_height": 2.0,
"range_min": 0.05,
"range_max": 90.0,
}
],
namespace=namespace,
)

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),
]


def generate_launch_description() -> LaunchDescription:
"""Generate the launch description for the realsense camera.

Returns:
LaunchDescription: The launch description for the realsense camera.
"""
return LaunchDescription(
[
use_sim_arg.declaration,
namespace_arg.declaration,
OpaqueFunction(function=launch_setup),
]
)
2 changes: 1 addition & 1 deletion ros2_ws/src/rcdt_sensors/urdf/rcdt_os1_128.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ Based on:
parent
name:=ouster
update_rate:=10
lasers:=128
lasers:=12
samples:=1024
min_range:=0.5
max_range:=90.0
Expand Down
Loading