Skip to content

Commit

Permalink
Merge pull request #209 from tier4/hotfix/perception/refactor_pointcl…
Browse files Browse the repository at this point in the history
…oud_container

feat(perception): refactor pointcloud container
  • Loading branch information
shmpwk authored Feb 2, 2024
2 parents 38c6db4 + dcf25c3 commit dfd3203
Show file tree
Hide file tree
Showing 11 changed files with 33 additions and 56 deletions.
3 changes: 1 addition & 2 deletions aip_x1_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,7 @@
<arg name="scan_phase" value="180.0" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="container_name" value="$(var pointcloud_container_name)"/>
<arg name="container_name" value="pointcloud_container"/>
</include>
</group>

Expand Down
7 changes: 4 additions & 3 deletions aip_x1_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ def launch_setup(context, *args, **kwargs):

# set container to run all required components in the same process
container = ComposableNodeContainer(
name=LaunchConfiguration("container_name"),
name=LaunchConfiguration("individual_container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
Expand All @@ -64,7 +64,7 @@ def launch_setup(context, *args, **kwargs):
target_container = (
container
if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
else LaunchConfiguration("container_name")
else LaunchConfiguration("pointcloud_container_name")
)

# load concat or passthrough filter
Expand All @@ -86,7 +86,8 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("use_multithread", "False")
add_launch_arg("use_intra_process", "False")
add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("container_name", "pointcloud_preprocessor_container")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg("individual_container_name", "concatenate_container")

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
4 changes: 2 additions & 2 deletions aip_x2_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -189,8 +189,8 @@
<arg name="base_frame" value="base_link" />
<arg name="use_intra_process" value="true" />
<arg name="use_multithread" value="true" />
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="container_name" value="$(var pointcloud_container_name)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>

</group>
Expand Down
7 changes: 4 additions & 3 deletions aip_x2_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ def launch_setup(context, *args, **kwargs):

# set container to run all required components in the same process
container = ComposableNodeContainer(
name=LaunchConfiguration("container_name"),
name=LaunchConfiguration("individual_container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
Expand All @@ -70,7 +70,7 @@ def launch_setup(context, *args, **kwargs):
target_container = (
container
if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
else LaunchConfiguration("container_name")
else LaunchConfiguration("pointcloud_container_name")
)

# load concat or passthrough filter
Expand All @@ -93,7 +93,8 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("use_multithread", "True")
add_launch_arg("use_intra_process", "True")
add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("container_name", "pointcloud_preprocessor_container")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg("individual_container_name", "concatenate_container")

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
16 changes: 6 additions & 10 deletions aip_xx1_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,7 @@
<arg name="scan_phase" value="300.0"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
<arg name="container_name" value="pointcloud_container"/>
</include>
</group>

Expand All @@ -40,8 +39,7 @@
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
<arg name="container_name" value="pointcloud_container"/>
</include>
</group>

Expand All @@ -58,8 +56,7 @@
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
<arg name="container_name" value="pointcloud_container"/>
</include>
</group>

Expand All @@ -76,8 +73,7 @@
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
<arg name="container_name" value="pointcloud_container"/>
</include>
</group>

Expand Down Expand Up @@ -105,8 +101,8 @@
<arg name="base_frame" value="base_link"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="use_pointcloud_container" value="true"/>
<arg name="container_name" value="/sensing/lidar/top/pointcloud_preprocessor/pointcloud_container"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>

</group>
Expand Down
16 changes: 5 additions & 11 deletions aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -57,32 +57,25 @@ def launch_setup(context, *args, **kwargs):
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

glog_component = ComposableNode(
package="glog_component",
plugin="GlogComponent",
name="glog_component",
)

# set container to run all required components in the same process
container = ComposableNodeContainer(
name=LaunchConfiguration("container_name"),
name=LaunchConfiguration("individual_container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=[glog_component],
condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
output="screen",
)

target_container = (
container
if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
else LaunchConfiguration("container_name")
else LaunchConfiguration("pointcloud_container_name")
)

# load concat or passthrough filter
concat_loader = LoadComposableNodes(
composable_node_descriptions=[concat_component, glog_component],
composable_node_descriptions=[concat_component],
target_container=target_container,
condition=IfCondition(LaunchConfiguration("use_concat_filter")),
)
Expand All @@ -100,7 +93,8 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("use_multithread", "False")
add_launch_arg("use_intra_process", "False")
add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("container_name", "pointcloud_preprocessor_container")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg("individual_container_name", "concatenate_container")

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
2 changes: 0 additions & 2 deletions common_sensor_launch/launch/hesai_XT32.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
<arg name="cloud_max_angle" default="360"/>
<arg name="dual_return_distance_threshold" default="0.1"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="use_pointcloud_container" default="false"/>
<arg name="container_name" default="hesai_node_container"/>

<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
Expand All @@ -32,7 +31,6 @@
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
</include>
</launch>
28 changes: 11 additions & 17 deletions common_sensor_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,14 @@ def create_parameter_dict(*args):

nodes = []

nodes.append(
ComposableNode(
package="glog_component",
plugin="GlogComponent",
name="glog_component",
)
)

nodes.append(
ComposableNode(
package="nebula_ros",
Expand Down Expand Up @@ -200,14 +208,7 @@ def create_parameter_dict(*args):
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=nodes,
condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
output="screen",
)

component_loader = LoadComposableNodes(
composable_node_descriptions=nodes,
target_container=LaunchConfiguration("container_name"),
condition=IfCondition(LaunchConfiguration("use_pointcloud_container")),
output="both",
)

driver_component = ComposableNode(
Expand Down Expand Up @@ -238,19 +239,13 @@ def create_parameter_dict(*args):
],
)

target_container = (
container
if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
else LaunchConfiguration("container_name")
)

driver_component_loader = LoadComposableNodes(
composable_node_descriptions=[driver_component],
target_container=target_container,
target_container=container,
condition=IfCondition(LaunchConfiguration("launch_driver")),
)

return [container, component_loader, driver_component_loader]
return [container, driver_component_loader]


def generate_launch_description():
Expand Down Expand Up @@ -287,7 +282,6 @@ def add_launch_arg(name: str, default_value=None, description=None):
)
add_launch_arg("use_multithread", "False", "use multithread")
add_launch_arg("use_intra_process", "False", "use ROS 2 component container communication")
add_launch_arg("use_pointcloud_container", "false")
add_launch_arg("container_name", "nebula_node_container")

set_container_executable = SetLaunchConfiguration(
Expand Down
2 changes: 0 additions & 2 deletions common_sensor_launch/launch/velodyne_VLP16.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="use_pointcloud_container" default="false"/>
<arg name="container_name" default="velodyne_node_container"/>

<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
Expand All @@ -34,7 +33,6 @@
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="false"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
</include>

Expand Down
2 changes: 0 additions & 2 deletions common_sensor_launch/launch/velodyne_VLP32C.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="use_pointcloud_container" default="false"/>
<arg name="container_name" default="velodyne_node_container"/>

<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
Expand All @@ -34,7 +33,6 @@
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_intra_process" value="false"/>
<arg name="use_multithread" value="false"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
</include>

Expand Down
2 changes: 0 additions & 2 deletions common_sensor_launch/launch/velodyne_VLS128.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="use_pointcloud_container" default="false"/>
<arg name="container_name" default="velodyne_node_container"/>

<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
Expand All @@ -34,7 +33,6 @@
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
</include>

Expand Down

0 comments on commit dfd3203

Please sign in to comment.