Skip to content

Commit

Permalink
Add multithread and intra process option (autowarefoundation#187)
Browse files Browse the repository at this point in the history
* Add multithread and intra process option

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Fix velodyne node container executable

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add option into aip_xx2

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add option into aip_x2

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add option into aip_x1

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add option into aip_s1

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add option into aip_customized

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add option into lidar.launch.xml

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>
  • Loading branch information
wep21 authored Apr 7, 2021
1 parent 21fac3b commit 443a524
Show file tree
Hide file tree
Showing 16 changed files with 319 additions and 68 deletions.
2 changes: 2 additions & 0 deletions sensing_launch/launch/aip_customized/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,8 @@
<arg name="base_frame" value="base_link" />
<arg name="use_concat_filter" value="$(var use_concat_filter)" />
<arg name="vehicle_param_file" value="$(var vehicle_param_file)" />
<arg name="use_intra_process" value="false" />
<arg name="use_multithread" value="false" />
</include>

</group>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
import yaml

import launch
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes
Expand Down Expand Up @@ -59,11 +59,14 @@ def launch_setup(context, *args, **kwargs):
remappings=[('output', 'concatenated/pointcloud')],
parameters=[{
'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud',
'/sensing/lidar/left/outlier_filtered/pointcloud',
'/sensing/lidar/right/outlier_filtered/pointcloud'],
'output_frame': 'base_link',
'/sensing/lidar/left/outlier_filtered/pointcloud',
'/sensing/lidar/right/outlier_filtered/pointcloud'],
'output_frame': LaunchConfiguration('base_frame'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
}],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
)

passthrough_component = ComposableNode(
Expand All @@ -75,11 +78,14 @@ def launch_setup(context, *args, **kwargs):
('output', 'concatenated/pointcloud'),
],
parameters=[{
'output_frame': 'base_link',
'output_frame': LaunchConfiguration('base_frame'),
'min_z': vehicle_info['min_height_offset'],
'max_z': vehicle_info['max_height_offset'],
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
}],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
)

# set crop box filter as a component
Expand All @@ -102,7 +108,10 @@ def launch_setup(context, *args, **kwargs):
'max_z': vehicle_info['max_height_offset'],
'negative': False,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
}],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
)

ground_component = ComposableNode(
Expand All @@ -118,15 +127,18 @@ def launch_setup(context, *args, **kwargs):
"local_max_slope": 10.0,
"min_height_threshold": 0.2,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
}],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
)

# set container to run all required components in the same process
container = ComposableNodeContainer(
name='pointcloud_preprocessor_container',
namespace='pointcloud_preprocessor',
package='rclcpp_components',
executable='component_container',
executable=LaunchConfiguration('container_executable'),
composable_node_descriptions=[
cropbox_component,
ground_component,
Expand All @@ -141,13 +153,13 @@ def launch_setup(context, *args, **kwargs):
concat_loader = LoadComposableNodes(
composable_node_descriptions=[concat_component],
target_container=container,
condition=launch.conditions.IfCondition(LaunchConfiguration('use_concat_filter')),
condition=IfCondition(LaunchConfiguration('use_concat_filter')),
)

passthrough_loader = LoadComposableNodes(
composable_node_descriptions=[passthrough_component],
target_container=container,
condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_concat_filter')),
condition=UnlessCondition(LaunchConfiguration('use_concat_filter')),
)

return [container, concat_loader, passthrough_loader]
Expand All @@ -162,5 +174,22 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg('base_frame', 'base_link')
add_launch_arg('use_concat_filter', 'use_concat_filter')
add_launch_arg('vehicle_param_file')
add_launch_arg('use_multithread', 'False')
add_launch_arg('use_intra_process', 'False')

set_container_executable = SetLaunchConfiguration(
'container_executable',
'component_container',
condition=UnlessCondition(LaunchConfiguration('use_multithread'))
)

set_container_mt_executable = SetLaunchConfiguration(
'container_executable',
'component_container_mt',
condition=IfCondition(LaunchConfiguration('use_multithread'))
)

return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)])
return launch.LaunchDescription(launch_arguments +
[set_container_executable,
set_container_mt_executable] +
[OpaqueFunction(function=launch_setup)])
2 changes: 2 additions & 0 deletions sensing_launch/launch/aip_s1/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,8 @@
<arg name="base_frame" value="base_link" />
<arg name="use_concat_filter" value="$(var use_concat_filter)" />
<arg name="vehicle_param_file" value="$(var vehicle_param_file)" />
<arg name="use_intra_process" value="false" />
<arg name="use_multithread" value="false" />
</include>

</group>
Expand Down
56 changes: 42 additions & 14 deletions sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@

# Copyright 2020 Tier IV, Inc. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
Expand All @@ -17,7 +16,7 @@
import yaml

import launch
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes
Expand Down Expand Up @@ -59,11 +58,14 @@ def launch_setup(context, *args, **kwargs):
remappings=[('output', 'concatenated/pointcloud')],
parameters=[{
'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud',
'/sensing/lidar/left/outlier_filtered/pointcloud',
'/sensing/lidar/right/outlier_filtered/pointcloud'],
'output_frame': 'base_link',
'/sensing/lidar/left/outlier_filtered/pointcloud',
'/sensing/lidar/right/outlier_filtered/pointcloud'],
'output_frame': LaunchConfiguration('base_frame'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
}],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
)

passthrough_component = ComposableNode(
Expand All @@ -75,11 +77,14 @@ def launch_setup(context, *args, **kwargs):
('output', 'concatenated/pointcloud'),
],
parameters=[{
'output_frame': 'base_link',
'output_frame': LaunchConfiguration('base_frame'),
'min_z': vehicle_info['min_height_offset'],
'max_z': vehicle_info['max_height_offset'],
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
}],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
)

# set crop box filter as a component
Expand All @@ -102,7 +107,10 @@ def launch_setup(context, *args, **kwargs):
'max_z': vehicle_info['max_height_offset'],
'negative': False,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
}],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
)

ground_component = ComposableNode(
Expand All @@ -118,15 +126,18 @@ def launch_setup(context, *args, **kwargs):
"local_max_slope": 10.0,
"min_height_threshold": 0.2,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
}],
extra_arguments=[{
'use_intra_process_comms': LaunchConfiguration('use_intra_process')
}],
)

# set container to run all required components in the same process
container = ComposableNodeContainer(
name='pointcloud_preprocessor_container',
namespace='pointcloud_preprocessor',
package='rclcpp_components',
executable='component_container',
executable=LaunchConfiguration('container_executable'),
composable_node_descriptions=[
cropbox_component,
ground_component,
Expand All @@ -141,13 +152,13 @@ def launch_setup(context, *args, **kwargs):
concat_loader = LoadComposableNodes(
composable_node_descriptions=[concat_component],
target_container=container,
condition=launch.conditions.IfCondition(LaunchConfiguration('use_concat_filter')),
condition=IfCondition(LaunchConfiguration('use_concat_filter')),
)

passthrough_loader = LoadComposableNodes(
composable_node_descriptions=[passthrough_component],
target_container=container,
condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_concat_filter')),
condition=UnlessCondition(LaunchConfiguration('use_concat_filter')),
)

return [container, concat_loader, passthrough_loader]
Expand All @@ -162,5 +173,22 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg('base_frame', 'base_link')
add_launch_arg('use_concat_filter', 'use_concat_filter')
add_launch_arg('vehicle_param_file')
add_launch_arg('use_multithread', 'False')
add_launch_arg('use_intra_process', 'False')

set_container_executable = SetLaunchConfiguration(
'container_executable',
'component_container',
condition=UnlessCondition(LaunchConfiguration('use_multithread'))
)

set_container_mt_executable = SetLaunchConfiguration(
'container_executable',
'component_container_mt',
condition=IfCondition(LaunchConfiguration('use_multithread'))
)

return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)])
return launch.LaunchDescription(launch_arguments +
[set_container_executable,
set_container_mt_executable] +
[OpaqueFunction(function=launch_setup)])
2 changes: 2 additions & 0 deletions sensing_launch/launch/aip_x1/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,8 @@
<arg name="use_concat_filter" value="$(var use_concat_filter)" />
<arg name="use_radius_search" value="$(var use_radius_search)" />
<arg name="vehicle_param_file" value="$(var vehicle_param_file)" />
<arg name="use_intra_process" value="false" />
<arg name="use_multithread" value="false" />
</include>

</group>
Expand Down
Loading

0 comments on commit 443a524

Please sign in to comment.