- 1. Introduction
- 2. Requirements
- 3. ROS API
- 4. Running ROS package with docker
- 5. Running ROS package without docker
- 6. Running ROS package with prerecorded dataset
- 7. Getting Started without ROS
Hybrid approach of Point Cloud Registration consists of main parts: downsampling cascade, WHI feature descriptor, fast multidimensional nearest neighbors graph-search, Max Clique Inlier Selection, transformation estimator of Fast Global Registration algorithm. It also include options to use FPFH feature descriptor, transformation estimator of Teaser++ and Plane-to-Plane ICP cascade for registration refinement. This approach allows for indoor global localization of devices that build a spatial map.
- ubuntu 20.04
- ros noetic
Subscribed Topics
- /global_map (sensor_msgs/PointCloud2): Topic of global map.
- /local_map (sensor_msgs/PointCloud2): Topic of current map.
Published Topics
- /tf2 (geometry_msgs/TransformStamped): Tf2 publish frames: frame_id -> child_id
Services
- /relocalize (std_srvs/Trigger): Service to manually run relocalization.
Parameters
№ | Name | Type | Default value | Description |
---|---|---|---|---|
1 | tf_pub_rate | float | 200 | Frame rate of TF publiser |
2 | parent_frame_id | string | map | Name of parent TF |
3 | child_frame_id | string | map_slam | Name of child TF |
4 | mode_pub_by_request | bool | true | True means performing transform and publication only by a request. False means performing transform and publication automatically when receive a new data. The node publishes TF with fixed rate in any mode. |
The easiest way to play with the package is to use docker. You can either build and run it manually, or use docker.sh
script.
Typically, you need to run one of following commands with this script:
./docker.sh build
to build a docker image./docker.sh run
to run it./docker.sh rviz
to run it with rviz./docker.sh help
to get additional info
Your installation process might be base don Dockerfile
.
The core of the package is pc_global_localization_node
node. To use it, you should load ros parameters.
The best way to use this node is to either use launch/run_pc_global_localization.launch
file or to write your own.
Let's say you have 2 pcd files in your folder named Map.pcd
and GlobalMap.pcd
.
You could play with this package by running following commands in different terminals:
./docker.sh rviz
rosrun pcl_ros pcd_to_pointcloud Map.pcd 1.0 _frame_id:=map cloud_pcd:=/local_map __name:=my_node2
rosrun pcl_ros pcd_to_pointcloud GlobalMap.pcd 1.0 _frame_id:=map_slam cloud_pcd:=/global_map __name:=my_node1
- Installation of Point Cloud Library (PCL):
$ sudo apt install libpcl-dev
- Dependence for external WHI feature library:
$ sudo apt install libopencv-dev
- Support to use multithreading:
$ sudo apt install libopenmpi-dev
From root folder:
$ mkdir build
$ cd build
$ cmake ..
$ make
From build folder:
$ ./PCRegistrationAlgorithmTest <target_point_cloud> <source_point_cloud>
- <target_point_cloud> and <source_point_cloud> are the point cloud files of pcd format.