Skip to content

Commit

Permalink
fix(probabilistic_occupancy_grid_map): fix launch config name from ol…
Browse files Browse the repository at this point in the history
…d one (autowarefoundation#6663)

fix: fix launch config name from old one

Signed-off-by: yoshiri <[email protected]>
  • Loading branch information
YoshiRi committed Apr 22, 2024
1 parent 253a484 commit c7db8b6
Showing 1 changed file with 9 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,12 @@ def launch_setup(context, *args, **kwargs):
gridmap_generation_composable_nodes = []

number_of_nodes = len(fusion_config["raw_pointcloud_topics"])
print(number_of_nodes)
print(
"launching multi_lidar_pointcloud_based occupancy grid map",
number_of_nodes,
"nodes in the container named",
LaunchConfiguration("pointcloud_container_name").perform(context),
)

for i in range(number_of_nodes):
# load parameter file
Expand Down Expand Up @@ -150,7 +155,7 @@ def launch_setup(context, *args, **kwargs):

# 3. launch setting
occupancy_grid_map_container = ComposableNodeContainer(
name=LaunchConfiguration("container_name"),
name=LaunchConfiguration("pointcloud_container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
Expand All @@ -161,7 +166,7 @@ def launch_setup(context, *args, **kwargs):

load_composable_nodes = LoadComposableNodes(
composable_node_descriptions=gridmap_generation_composable_nodes + gridmap_fusion_node,
target_container=LaunchConfiguration("container_name"),
target_container=LaunchConfiguration("pointcloud_container_name"),
condition=IfCondition(LaunchConfiguration("use_pointcloud_container")),
)

Expand Down Expand Up @@ -189,7 +194,7 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("use_multithread", "false"),
add_launch_arg("use_intra_process", "true"),
add_launch_arg("use_pointcloud_container", "false"),
add_launch_arg("container_name", "occupancy_grid_map_container"),
add_launch_arg("pointcloud_container_name", "occupancy_grid_map_container"),
add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"),
add_launch_arg("output", "occupancy_grid"),
add_launch_arg(
Expand Down

0 comments on commit c7db8b6

Please sign in to comment.