Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(tier4_simulator_launch): fix occupancy grid map not appearing problem in psim #3081

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,6 @@ def launch_setup(context, *args, **kwargs):
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 @@ -86,7 +80,15 @@ def launch_setup(context, *args, **kwargs):
("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")),
("~/output/occupancy_grid_map", LaunchConfiguration("output")),
],
parameters=[laserscan_based_occupancy_grid_map_node_params],
parameters=[
laserscan_based_occupancy_grid_map_node_params,
{
"input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"),
"input_obstacle_and_raw_pointcloud": LaunchConfiguration(
"input_obstacle_and_raw_pointcloud"
),
},
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
),
]
Expand Down
13 changes: 5 additions & 8 deletions launch/tier4_simulator_launch/launch/simulator.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -39,15 +39,12 @@
<group unless="$(var scenario_simulation)">
<!-- Occupancy Grid -->
<push-ros-namespace namespace="occupancy_grid_map"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py">
<arg name="input/obstacle_pointcloud" value="/perception/obstacle_segmentation/single_frame/pointcloud_raw"/>
<arg name="input/raw_pointcloud" value="/sensing/lidar/concatenated/pointcloud"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py">
<arg name="input_obstacle_pointcloud" value="true"/>
<arg name="input_obstacle_and_raw_pointcloud" value="false"/>
<arg name="input/obstacle_pointcloud" value="/perception/obstacle_segmentation/pointcloud"/>
<arg name="output" value="/perception/occupancy_grid_map/map"/>
<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="param_file" value="$(find-pkg-share probabilistic_occupancy_grid_map)/config/pointcloud_based_occupancy_grid_map.param.yaml"/>
<arg name="param_file" value="$(find-pkg-share probabilistic_occupancy_grid_map)/config/laserscan_based_occupancy_grid_map.param.yaml"/>
</include>
</group>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,5 +12,3 @@
map_length: 100.0
map_width: 100.0
map_resolution: 0.5
input_obstacle_pointcloud: true
input_obstacle_and_raw_pointcloud: true
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
Expand All @@ -30,12 +31,6 @@ def launch_setup(context, *args, **kwargs):
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 @@ -85,7 +80,15 @@ def launch_setup(context, *args, **kwargs):
("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")),
("~/output/occupancy_grid_map", LaunchConfiguration("output")),
],
parameters=[laserscan_based_occupancy_grid_map_node_params],
parameters=[
laserscan_based_occupancy_grid_map_node_params,
{
"input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"),
"input_obstacle_and_raw_pointcloud": LaunchConfiguration(
"input_obstacle_and_raw_pointcloud"
),
},
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
),
]
Expand Down Expand Up @@ -138,7 +141,11 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("output/stixel", "virtual_scan/stixel"),
add_launch_arg("input_obstacle_pointcloud", "false"),
add_launch_arg("input_obstacle_and_raw_pointcloud", "true"),
add_launch_arg("param_file", "config/laserscan_based_occupancy_grid_map.param.yaml"),
add_launch_arg(
"param_file",
get_package_share_directory("probabilistic_occupancy_grid_map")
+ "/config/laserscan_based_occupancy_grid_map.param.yaml",
),
add_launch_arg("use_pointcloud_container", "false"),
add_launch_arg("container_name", "occupancy_grid_map_container"),
set_container_executable,
Expand Down