Skip to content

Commit

Permalink
feat: always separate lidar preprocessing from pointcloud_container (#85
Browse files Browse the repository at this point in the history
)

* feat!: replace use_pointcloud_container

Signed-off-by: kminoda <[email protected]>

* style(pre-commit): autofix

* fix: now works

Signed-off-by: kminoda <[email protected]>

* revert: revert unnecessary change

Signed-off-by: kminoda <[email protected]>

* include_concat_node_in_pointcloud_container to use_pointcloud_container

Signed-off-by: kminoda <[email protected]>

* style(pre-commit): autofix

* fix arg name

Signed-off-by: kminoda <[email protected]>

---------

Signed-off-by: kminoda <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
kminoda and pre-commit-ci[bot] authored Jan 19, 2024
1 parent 5ccd754 commit a6a7063
Show file tree
Hide file tree
Showing 5 changed files with 12 additions and 33 deletions.
20 changes: 3 additions & 17 deletions common_sensor_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -200,16 +200,9 @@ 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")),
)

driver_component = ComposableNode(
package="nebula_ros",
plugin=sensor_make + "HwInterfaceRosWrapper",
Expand Down Expand Up @@ -238,19 +231,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,8 +274,7 @@ 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")
add_launch_arg("lidar_container_name", "nebula_node_container")

set_container_executable = SetLaunchConfiguration(
"container_executable",
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 @@ -13,7 +13,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 @@ -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="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 @@ -13,7 +13,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 @@ -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>

Expand Down
14 changes: 5 additions & 9 deletions sample_sensor_kit_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,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 @@ -39,8 +38,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 @@ -57,8 +55,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 @@ -75,8 +72,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 @@ -85,7 +81,7 @@
<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="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,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 @@ -63,7 +63,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

0 comments on commit a6a7063

Please sign in to comment.