Skip to content

Commit

Permalink
Move parameters of point cloud divider to xml files
Browse files Browse the repository at this point in the history
Signed-off-by: Anh Nguyen <anh.nguyen.2@tier4.jp>
  • Loading branch information
anhnv3991 committed Mar 3, 2025
1 parent 7e9ab3e commit ab500c6
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 21 deletions.
27 changes: 6 additions & 21 deletions map/autoware_pointcloud_divider/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,14 +30,19 @@ colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release --catkin-skip-building-test
- Select directory, process all files found with `find $INPUT_DIR -name "*.pcd"`.

```bash
ros2 launch autoware_pointcloud_divider pointcloud_divider.launch.xml input_pcd_or_dir:=<INPUT_DIR> output_pcd_dir:=<OUTPUT_DIR> prefix:=<PREFIX>
ros2 launch autoware_pointcloud_divider pointcloud_divider.launch.xml input_pcd_or_dir:=<INPUT_DIR> output_pcd_dir:=<OUTPUT_DIR> prefix:=<PREFIX> [use_large_grid:=true/false] [leaf_size:=<LEAF_SIZE>] [grid_size_x:=<GRID_SIZE_X>] [grid_size_y:=<GRID_SIZE_Y>]
```

| Name | Description |
| ---------- | ------------------------------------- |
| INPUT_DIR | Directory that contains all PCD files |
| OUTPUT_DIR | Output directory name |
| PREFIX | Prefix of output PCD file name |
| use_large_grid| If true, group PCD segments to groups of larger grids|
| LEAF_SIZE| The resolution (m) to downsample output PCD files. If negative, no downsampling is applied on the output PCD files|
| GRID_SIZE_X| The X size (m) of the output PCD segments|
| GRID_SIZE_Y| The Y size (m) of the output PCD segments|


`INPUT_DIR` and `OUTPUT_DIR` should be specified as **absolute paths**.

Expand All @@ -55,26 +60,6 @@ How the PCD file is named

![node_diagram](docs/output_file_name_pattern.drawio.svg)

### Parameter example

1. Dividing point clouds without downsampling

```yaml
use_large_grid: false
leaf_size: -1.0 # any negative number
grid_size_x: 20
grid_size_y: 20
```
2. Dividing and downsampling point clouds
```yaml
use_large_grid: false
leaf_size: 0.2
grid_size_x: 20
grid_size_y: 20
```
## Metadata YAML Format

The metadata file should be named `metadata.yaml`. It contains the following fields:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,25 @@
<launch>
<arg name="config_file_path" default="$(find-pkg-share autoware_pointcloud_divider)/config/pointcloud_divider.param.yaml" description="Path to the configuration YAML file"/>
<arg name="use_large_grid" default="false" description="True: group PCD files into folders"/>
<arg name="leaf_size" default="-0.1" description="Downsampling resolution"/>
<arg name="grid_size_x" default="20.0" description="The X size of a segment"/>
<arg name="grid_size_y" default="20.0" description="The Y size of a segment"/>
<arg name="input_pcd_or_dir" description="The path to the folder containing the input PCD files or the input PCD file"/>
<arg name="output_pcd_dir" description="The path to the folder containing the output PCD files and metadata files"/>
<arg name="prefix" default="" description="The prefix for output PCD files"/>
<arg name="point_type" default="point_xyzi" description="The type of map points"/>

<group>
<node pkg="autoware_pointcloud_divider" exec="autoware_pointcloud_divider_node" name="pointcloud_divider" output="screen">
<param from="$(var config_file_path)" allow_substs="true"/>
<param name="use_large_grid" value="$(var use_large_grid)"/>
<param name="leaf_size" value="$(var leaf_size)"/>
<param name="grid_size_x" value="$(var grid_size_x)"/>
<param name="grid_size_y" value="$(var grid_size_y)"/>
<param name="input_pcd_or_dir" value="$(var input_pcd_or_dir)"/>
<param name="output_pcd_dir" value="$(var output_pcd_dir)"/>
<param name="prefix" value="$(var prefix)"/>
<param name="point_type" value="$(var point_type)"/>
</node>
</group>
</launch>

0 comments on commit ab500c6

Please sign in to comment.