diff --git a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py index 6374178b2..835089288 100644 --- a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py @@ -57,26 +57,11 @@ def generate_launch_description(): 'max_x': 100.0, 'min_y': -50.0, 'max_y': 50.0, - 'min_z': -2.0, - 'max_z': 3.0, 'negative': False, } ] ) - passthrough_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PassThroughFilterComponent', - name='passthrough_filter', - remappings=[ - ('/input', 'top/rectified/pointcloud'), - ('/output', 'concatenated/pointcloud') - ], - parameters=[{ - 'output_frame': 'base_link', - }] - ) - ground_component = ComposableNode( package=pkg, plugin='pointcloud_preprocessor::RayGroundFilterComponent', @@ -112,7 +97,6 @@ def generate_launch_description(): composable_node_descriptions=[ concat_component, cropbox_component, - passthrough_component, ground_component, relay_component, ], diff --git a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py index 6374178b2..835089288 100644 --- a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py @@ -57,26 +57,11 @@ def generate_launch_description(): 'max_x': 100.0, 'min_y': -50.0, 'max_y': 50.0, - 'min_z': -2.0, - 'max_z': 3.0, 'negative': False, } ] ) - passthrough_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PassThroughFilterComponent', - name='passthrough_filter', - remappings=[ - ('/input', 'top/rectified/pointcloud'), - ('/output', 'concatenated/pointcloud') - ], - parameters=[{ - 'output_frame': 'base_link', - }] - ) - ground_component = ComposableNode( package=pkg, plugin='pointcloud_preprocessor::RayGroundFilterComponent', @@ -112,7 +97,6 @@ def generate_launch_description(): composable_node_descriptions=[ concat_component, cropbox_component, - passthrough_component, ground_component, relay_component, ], diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 6374178b2..835089288 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -57,26 +57,11 @@ def generate_launch_description(): 'max_x': 100.0, 'min_y': -50.0, 'max_y': 50.0, - 'min_z': -2.0, - 'max_z': 3.0, 'negative': False, } ] ) - passthrough_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PassThroughFilterComponent', - name='passthrough_filter', - remappings=[ - ('/input', 'top/rectified/pointcloud'), - ('/output', 'concatenated/pointcloud') - ], - parameters=[{ - 'output_frame': 'base_link', - }] - ) - ground_component = ComposableNode( package=pkg, plugin='pointcloud_preprocessor::RayGroundFilterComponent', @@ -112,7 +97,6 @@ def generate_launch_description(): composable_node_descriptions=[ concat_component, cropbox_component, - passthrough_component, ground_component, relay_component, ], diff --git a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py index 6374178b2..835089288 100644 --- a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py @@ -57,26 +57,11 @@ def generate_launch_description(): 'max_x': 100.0, 'min_y': -50.0, 'max_y': 50.0, - 'min_z': -2.0, - 'max_z': 3.0, 'negative': False, } ] ) - passthrough_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PassThroughFilterComponent', - name='passthrough_filter', - remappings=[ - ('/input', 'top/rectified/pointcloud'), - ('/output', 'concatenated/pointcloud') - ], - parameters=[{ - 'output_frame': 'base_link', - }] - ) - ground_component = ComposableNode( package=pkg, plugin='pointcloud_preprocessor::RayGroundFilterComponent', @@ -112,7 +97,6 @@ def generate_launch_description(): composable_node_descriptions=[ concat_component, cropbox_component, - passthrough_component, ground_component, relay_component, ], diff --git a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py index 6374178b2..835089288 100644 --- a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py @@ -57,26 +57,11 @@ def generate_launch_description(): 'max_x': 100.0, 'min_y': -50.0, 'max_y': 50.0, - 'min_z': -2.0, - 'max_z': 3.0, 'negative': False, } ] ) - passthrough_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PassThroughFilterComponent', - name='passthrough_filter', - remappings=[ - ('/input', 'top/rectified/pointcloud'), - ('/output', 'concatenated/pointcloud') - ], - parameters=[{ - 'output_frame': 'base_link', - }] - ) - ground_component = ComposableNode( package=pkg, plugin='pointcloud_preprocessor::RayGroundFilterComponent', @@ -112,7 +97,6 @@ def generate_launch_description(): composable_node_descriptions=[ concat_component, cropbox_component, - passthrough_component, ground_component, relay_component, ], diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py index d3a73f874..94b979ba2 100644 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -20,6 +20,13 @@ from launch_ros.descriptions import ComposableNode import uuid + +def acceptable_unique_name(prefix): + id = str(uuid.uuid4()) + # ros2 apparently doesn't accept the UUID with hyphens in node names + return prefix + id.replace('-', '_') + + def generate_launch_description(): launch_arguments = [] @@ -128,26 +135,22 @@ def create_parameter_dict(*args): # set container to run all required components in the same process container = ComposableNodeContainer( - name=LaunchConfiguration('container_name'), + # need unique name, otherwise all processes in same container and the node names then clash + name=acceptable_unique_name('velodyne_node_container'), namespace='pointcloud_preprocessor', package='rclcpp_components', executable='component_container', composable_node_descriptions=nodes, ) - def acceptable_unique_name(prefix='velodyne-driver-node'): - id = str(uuid.uuid4()) - # ros2 doesn't accept hyphens in node names - return prefix + id.replace('-', '_') - driver_component = ComposableNode( package='velodyne_driver', plugin='velodyne_driver::VelodyneDriver', # node is created in a global context, need to avoid name clash - name=acceptable_unique_name(), + name='velodyne_driver', parameters=[create_parameter_dict('device_ip', 'frame_id', 'model', 'pcap', 'port', 'read_fast', 'read_once', 'repeat_delay', 'rpm')], - ) + ) # one way to add a ComposableNode conditional on a launch argument to a # container. The `ComposableNode` itself doesn't accept a condition