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

feat(tier4_perception_launch): refactored occupancy_grid_map launcher #3058

This file was deleted.

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
<?xml version="1.0"?>
<launch>
<!--default parameter follows node setting -->
<arg name="input/obstacle_pointcloud" default="concatenated/pointcloud"/>
<arg name="input/raw_pointcloud" default="no_ground/oneshot/pointcloud"/>
<arg name="output" default="/perception/occupancy_grid_map/map"/>
<arg name="use_intra_process" default="false"/>
<arg name="use_multithread" default="false"/>
<arg name="use_pointcloud_container" default="false"/>
<arg name="container_name" default="occupancy_grid_map_container"/>
<arg name="scan_origin" default="base_link"/>
<arg name="map_origin" default="base_link"/>

<!--default parameter follows node setting -->
<arg name="method" default="pointcloud_based_occupancy_grid_map"/>
<arg name="param_file" default="$(find-pkg-share probabilistic_occupancy_grid_map)/config/$(var method).param.yaml"/>

<!--pointcloud based method-->
<group if="$(eval &quot;'$(var method)'=='pointcloud_based_occupancy_grid_map'&quot;)">
<include file="$(find-pkg-share probabilistic_occupancy_grid_map)/launch/pointcloud_based_occupancy_grid_map.launch.py">
<arg name="input/obstacle_pointcloud" value="$(var input/obstacle_pointcloud)"/>
<arg name="input/raw_pointcloud" value="$(var input/raw_pointcloud)"/>
<arg name="output" value="$(var output)"/>
<arg name="use_intra_process" value="$(var use_intra_process)"/>
<arg name="use_multithread" value="$(var use_multithread)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
<arg name="param_file" value="$(var param_file)"/>
<arg name="scan_origin" value="$(var scan_origin)"/>
<arg name="map_origin" value="$(var map_origin)"/>
</include>
</group>

<!--laserscan based method-->
<group if="$(eval &quot;'$(var method)'=='laserscan_based_occupancy_grid_map'&quot;)">
<include file="$(find-pkg-share probabilistic_occupancy_grid_map)/launch/laserscan_based_occupancy_grid_map.launch.py">
<arg name="input/obstacle_pointcloud" value="$(var input/obstacle_pointcloud)"/>
<arg name="input/raw_pointcloud" value="$(var input/raw_pointcloud)"/>
<arg name="output" value="$(var output)"/>
<arg name="use_intra_process" value="$(var use_intra_process)"/>
<arg name="use_multithread" value="$(var use_multithread)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
<arg name="param_file" value="$(var param_file)"/>
<arg name="scan_origin" value="$(var scan_origin)"/>
<arg name="map_origin" value="$(var map_origin)"/>
</include>
</group>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -68,14 +68,15 @@
<!-- occupancy grid map module -->
<group>
<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">
<include file="$(find-pkg-share tier4_perception_launch)/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml">
<arg name="input/obstacle_pointcloud" value="/perception/obstacle_segmentation/single_frame/pointcloud_raw"/>
<arg name="input/raw_pointcloud" value="$(var input/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="method" value="pointcloud_based_occupancy_grid_map"/>
<arg name="param_file" value="$(find-pkg-share probabilistic_occupancy_grid_map)/config/pointcloud_based_occupancy_grid_map.param.yaml"/>
</include>
</group>
Expand Down
23 changes: 20 additions & 3 deletions perception/probabilistic_occupancy_grid_map/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,11 @@
This package outputs the probability of having an obstacle as occupancy grid map.
![pointcloud_based_occupancy_grid_map_sample_image](./image/pointcloud_based_occupancy_grid_map_sample_image.gif)

## References/External links

- [Pointcloud based occupancy grid map](pointcloud-based-occupancy-grid-map.md)
- [Laserscan based occupancy grid map](laserscan-based-occupancy-grid-map.md)

## Settings

Occupancy grid map is generated on `map_frame`, and grid orientation is fixed.
Expand Down Expand Up @@ -46,7 +51,19 @@ Config parameters are managed in `config/*.yaml` and here shows its outline.
| scan_origin_frame | "base_link" |
| gridmap_origin_frame | "base_link" |

## References/External links
## Other parameters

- [Pointcloud based occupancy grid map](pointcloud-based-occupancy-grid-map.md)
- [Laserscan based occupancy grid map](laserscan-based-occupancy-grid-map.md)
Additional argument is shown below:

| Name | Default | Description |
| ----------------------------------------------- | ------------------------------ | ----------------------------------------------------------------------------------------------------------------------------------------- |
| `use_multithread` | `false` | whether to use multithread |
| `use_intra_process` | `false` | |
| `map_origin` | `` | parameter to override `map_origin_frame` which means grid map origin |
| `scan_origin` | `` | parameter to override `scan_origin_frame` which means scanning center |
| `output` | `occupancy_grid` | output name |
| `use_pointcloud_container` | `false` | |
| `container_name` | `occupancy_grid_map_container` | |
| `filter_obstacle_pointcloud_by_raw_pointcloud_` | `false` | only for pointcloud based method. If true, the node use raw pointcloud to filter obstacle pointcloud. Options for the limited FOV sensor. |
| `input_obstacle_pointcloud` | `false` | only for laserscan based method. If true, the node subscribe obstacle pointcloud |
| `input_obstacle_and_raw_pointcloud` | `true` | only for laserscan based method. If true, the node subscribe both obstacle and raw pointcloud |
Loading