Skip to content

Commit

Permalink
fixed laserscan based launcher
Browse files Browse the repository at this point in the history
Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
  • Loading branch information
YoshiRi committed Mar 11, 2023
1 parent a3c78d0 commit 41e878a
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,15 @@

def launch_setup(context, *args, **kwargs):
# load parameter files
param_file = LaunchConfiguration("param_file").parse(context)
param_file = LaunchConfiguration("param_file").perform(context)
with open(param_file, "r") as f:
laserscan_based_occupancy_grid_map_node_params = yaml.safe_load(f)["/**"]["ros__parameters"]
laserscan_based_occupancy_grid_map_node_params["input_obstacle_pointcloud"] = bool(
LaunchConfiguration("input_obstacle_pointcloud").perform(context)
)
laserscan_based_occupancy_grid_map_node_params["input_obstacle_and_raw_pointcloud"] = bool(
LaunchConfiguration("input_obstacle_and_raw_pointcloud").perform(context)
)

composable_nodes = [
ComposableNode(
Expand Down Expand Up @@ -79,14 +85,7 @@ def launch_setup(context, *args, **kwargs):
("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")),
("~/output/occupancy_grid_map", LaunchConfiguration("output")),
],
parameters=[
{
"input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"),
"input_obstacle_and_raw_pointcloud": LaunchConfiguration(
"input_obstacle_and_raw_pointcloud"
),
}.update(laserscan_based_occupancy_grid_map_node_params)
],
parameters=[laserscan_based_occupancy_grid_map_node_params],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
),
]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,15 @@

def launch_setup(context, *args, **kwargs):
# load parameter files
param_file = LaunchConfiguration("param_file").parse(context)
param_file = LaunchConfiguration("param_file").perform(context)
with open(param_file, "r") as f:
laserscan_based_occupancy_grid_map_node_params = yaml.safe_load(f)["/**"]["ros__parameters"]
laserscan_based_occupancy_grid_map_node_params["input_obstacle_pointcloud"] = bool(
LaunchConfiguration("input_obstacle_pointcloud").perform(context)
)
laserscan_based_occupancy_grid_map_node_params["input_obstacle_and_raw_pointcloud"] = bool(
LaunchConfiguration("input_obstacle_and_raw_pointcloud").perform(context)
)

composable_nodes = [
ComposableNode(
Expand Down Expand Up @@ -79,14 +85,7 @@ def launch_setup(context, *args, **kwargs):
("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")),
("~/output/occupancy_grid_map", LaunchConfiguration("output")),
],
parameters=[
{
"input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"),
"input_obstacle_and_raw_pointcloud": LaunchConfiguration(
"input_obstacle_and_raw_pointcloud"
),
}.update(laserscan_based_occupancy_grid_map_node_params)
],
parameters=[laserscan_based_occupancy_grid_map_node_params],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
),
]
Expand Down

0 comments on commit 41e878a

Please sign in to comment.