Skip to content

Commit dfd4abf

Browse files
committed
Updated the readme and added respawn to nodes in order to allow
automatic restart in case of unexpected problems.
1 parent 99114cd commit dfd4abf

3 files changed

Lines changed: 136 additions & 4 deletions

File tree

README.md

Lines changed: 134 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,136 @@
1-
Dynamic-Robot-Localization
1+
Dynamic Robot Localization
22
==================
33

4-
Dynamic Robot localization
4+
5+
# Overview
6+
7+
The dynamic_robot_localization is a ROS package that offers 3 DOF and 6 DOF localization using PCL and allows dynamic map update using OctoMap.
8+
It's a modular localization pipeline, that can be configured using yaml files (detailed configuration layout available in [drl_configs.yaml](https://github.com/carlosmccosta/dynamic_robot_localization/blob/hydro-devel/yaml/schema/drl_configs.yaml))
9+
10+
11+
12+
# Data sources
13+
14+
The localization system can operate with any type of sensors that provide point clouds.
15+
As such, it can use any number of laser sensors (by using the [laserscan_to_pointcloud](https://github.com/carlosmccosta/laserscan_to_pointcloud) package) or RGB-D / ToF cameras.
16+
17+
18+
19+
# Reference map
20+
21+
The reference map can be provided to the localization system from CAD ( .ply | .stl | .obj | .vtk ), pointcloud file (.pcd) / topic (sensor_msgs::PointCloud2) or using a 2D costmap (nav_msgs::OccupancyGrid).
22+
To avoid unnecessary overhead it should be provided has pointcloud (.pcd).
23+
24+
To convert CAD files to .pcd there are two options:
25+
26+
1. Using [conversion scripts](https://github.com/carlosmccosta/dynamic_robot_localization/tree/hydro-devel/tools) that filter the CAD using meshlabserver, add point curvature information and convert the CAD to .pcd (recommended)
27+
- Supported file types: .3ds .aln .apts .asc .dae .gts .obj .off .ply .pts .ptx .stl .tri .v3d .vrml .x3d .x3dv .xyz
28+
2. Using the [mesh_to_pointcloud](https://github.com/carlosmccosta/mesh_to_pointcloud) package that converts CAD to .pcd directly (without curvature and filtering)
29+
- Supported file types: .3dc .3ds .asc .ac .bsp .dae .dw .dxf .fbx .flt .gem .geo .iv .ive .logo .lwo .lw .lws .md2 .obj .ogr .osg .pfb .ply .shp .stl .x .wrl
30+
31+
32+
33+
# Localization methods
34+
35+
The localization system has two different localization methods to tackle different scenarios.
36+
For initial pose estimation and pose recovery it can use feature matching with several keypoint detectors (such as Scale Invariant Feature Transform (SIFT) and Intrinsic Shape Signatures (ISS3D)) and several keypoint descriptors (such as Point Feature Histogram (PFH), Fast Point Feature Histogram (FPFH), Signature of Histograms of Orientations (SHOT), Shape Context 3D (SC3D), Unique Shape Context (USC) and Ensemble of Shape Functions (ESF)).
37+
For pose tracking it can use several variants of the Iterative Closest Point algorithm and also the Normal Distributions Transform (NDT).
38+
Moreover, pose tracking can have two configurations. One tuned for the expected operation conditions of the robot and another able to recover from odometry estimation problems (the system can operate without odometry).
39+
This gives the possibility to have a configuration that can perform pose tracking with the minimum amount of computational resources required (such as point-to-point ICP) and a more robust (and computational expensive) configuration to handle temporary tracking problems (such as point-to-point non linear ICP, point-to-plane ICP, generalized ICP).
40+
Examples of the localization pipeline are available at [dynamic_robot_localization/yaml/configs](https://github.com/carlosmccosta/dynamic_robot_localization/tree/hydro-devel/yaml/configs)
41+
42+
43+
44+
# Localization reliability
45+
46+
The localization pipeline allows the attachment of transformation validators before publishing pose estimations.
47+
They can be used to suppress estimations that are not plausible for a given robot operation conditions.
48+
These validators can suppress localization estimations in which the pose correction has a [ outlier percentage | inliers root mean square error | inliers / outliers angular distribution | translation / rotation corrections ] outside acceptable thresholds.
49+
If the tracking methods can't recover after a given amount of sensor updates / time, the initial pose estimation (using features) can be activated.
50+
51+
52+
53+
# Dynamic map update
54+
55+
Dynamic map update can be performed with the [OctoMap package](http://octomap.github.io/)
56+
This can be [achieved](https://github.com/carlosmccosta/dynamic_robot_localization/blob/hydro-devel/launch/octo_map.launch) by configuring either the registered cloud or the outlier cloud as input for OctoMap and the output of OctoMap as the reference cloud for the localization system.
57+
58+
59+
60+
# Usage
61+
62+
The localization system can be started with [dynamic_robot_localization_system.launch](https://github.com/carlosmccosta/dynamic_robot_localization/blob/hydro-devel/launch/dynamic_robot_localization_system.launch)
63+
64+
This launch file starts the nodes:
65+
66+
* dynamic_robot_localization
67+
* pose_to_tf_publisher (can be disabled)
68+
* laserscan_to_pointcloud_assembler (can be disabled)
69+
* octomap (can be disabled)
70+
71+
The localization is integrated with other ROS nodes by publishing TF transforms between map and odom frames (configurable frame names) using the [pose_to_tf_publisher node](https://github.com/carlosmccosta/pose_to_tf_publisher).
72+
The dynamic_robot_localization node publishes geometry_msgs::PoseStamped / geometry_msgs::PoseWithCovarianceStamped that are received by pose_to_tf_publisher and converted to TF messages.
73+
The TF is published in a separate ROS node to ensure that the system remains operational and with constant TF publish rate even if the localization node has variable computational time.
74+
Moreover, in the remote case that the localization system crashes (by lack of system resources, programming error in the localization node or in one of its external libraries), the system can remain operational using only odometry for a given amount of time (i.e. TF messages can be published continuously, with a timeout counted after the last valid pose estimation or one message for each pose estimation) and the localization node can be restarted without any impact in the rest of the system.
75+
76+
The dynamic_robot_localization node publishes in latched topics (if required, as the publish of these messages can be disabled to reduce consumption of system resources):
77+
78+
1. dynamic_robot_localization::LocalizationDetailed
79+
- Message that has detailed information about the localization estimation (number of registered points | number of inliers | outlier percentage | inliers root mean square error | inliers / outliers angular distribution | translation / rotation corrections | global estimation accepted poses)
80+
2. dynamic_robot_localization::LocalizationTimes
81+
- Message with the computation time of each localization processing stage (and also the global time)
82+
3. dynamic_robot_localization::LocalizationDiagnostics
83+
- Message with diagnostics (currently only has the point clouds size after each major localization pipeline stages)
84+
4. Registered clouds (sensor_msgs::PointCloud2)
85+
- The full registered cloud or its points categorized as inliers / outliers (computed in each pose estimation) is also published as 3 separated point clouds.
86+
5. Reference point cloud (sensor_msgs::PointCloud2)
87+
- The current reference point cloud is also published in order to be available to localization supervisors
88+
89+
90+
91+
# Dynamic robot localization tests
92+
93+
The localization system is being tested using two different robot platforms (Guardian and Jarvis), both in simulation and with the real robots in the INESC CROB lab.
94+
95+
The guardian platform uses the Gazebo simulator with the [guardian-ros-pkg](https://github.com/inesc/guardian-ros-pkg)
96+
The jarvis platform uses the Stage simulator.
97+
98+
Besides the CROB lab environment, the guardian platform was also tested in a ship interior with different configurations (with increasing level of difficulty for the localization system):
99+
100+
* static
101+
* static with unstable ground
102+
* static with cluttered environment
103+
* dynamic with cluttered environment
104+
105+
The testing configurations are managed in [localization_tests.launch](https://github.com/carlosmccosta/dynamic_robot_localization_tests/blob/hydro-devel/launch/localization_tests.launch)
106+
107+
They can use live data from the gazebo simulator or using [rosbags](https://github.com/carlosmccosta/dynamic_robot_localization_tests/tree/hydro-devel/datasets)
108+
109+
The test results along with environment screenshots / videos are available in [this shared folder](https://www.dropbox.com/sh/nwb6gezj2dan187/AABM2u4BGd12lN__nYFwSktLa?dl=0)
110+
111+
112+
113+
# Installation and package dependencies
114+
115+
Installation scripts can be found in this [shared folder.](https://www.dropbox.com/sh/fkio31gyt55oolj/AACGFB2gB5eH-o8B0Cc4qeHma?dl=0)
116+
117+
118+
119+
# List of related git repositories:
120+
121+
* [dynamic_robot_localization_tests](https://github.com/carlosmccosta/dynamic_robot_localization_tests)
122+
* [pose_to_tf_publisher](https://github.com/carlosmccosta/pose_to_tf_publisher)
123+
* [laserscan_to_pointcloud](https://github.com/carlosmccosta/laserscan_to_pointcloud)
124+
* [mesh_to_pointcloud](https://github.com/carlosmccosta/mesh_to_pointcloud)
125+
* [robot_localization_tools](https://github.com/carlosmccosta/robot_localization_tools)
126+
* [octomap_mapping](https://github.com/carlosmccosta/octomap_mapping)
127+
128+
129+
130+
# More info
131+
132+
* [ICIT 2015 paper](https://www.dropbox.com/sh/yizj93xtvsapl9e/AABdCPKrMX2V58vzpzECKiExa?dl=0)
133+
* [Results folder](https://www.dropbox.com/sh/nwb6gezj2dan187/AABM2u4BGd12lN__nYFwSktLa?dl=0)
134+
* [Dissertation webpage](http://carlosmccosta.wix.com/personal-webpage#!dissertation/c12dl)
135+
* [Dissertation abstract](http://1drv.ms/1odZRYO)
136+
* [Research](http://1drv.ms/1l8yGei)

launch/dynamic_robot_localization_system.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@
4242

4343
<!-- ==================================================== localization system ============================================= -->
4444
<!-- <node pkg="dynamic_robot_localization" type="drl_localization_node" name="drl_localization_node" ns="dynamic_robot_localization" output="screen" launch-prefix="gdbserver localhost:1337" > -->
45-
<node pkg="dynamic_robot_localization" type="drl_localization_node" name="drl_localization_node" ns="dynamic_robot_localization" output="screen">
45+
<node pkg="dynamic_robot_localization" type="drl_localization_node" name="drl_localization_node" respawn="true" ns="dynamic_robot_localization" output="screen">
4646
<param name="frame_ids/map_frame_id" type="str" value="$(arg map_frame_id)" />
4747
<param name="frame_ids/odom_frame_id" type="str" value="$(arg odom_frame_id)" />
4848
<param name="frame_ids/base_link_frame_id" type="str" value="$(arg base_link_frame_id)" />

launch/octo_map.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
<arg name="sensor_frame_id" default="hokuyo_tilt_laser_link" />
66
<arg name="cloud_in" default="aligned_pointcloud_outliers" />
77

8-
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server" args="$(arg octomap_file)" ns="dynamic_robot_localization" output="screen">
8+
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server" args="$(arg octomap_file)" respawn="true" ns="dynamic_robot_localization" output="screen">
99
<param name="frame_id" type="string" value="map" />
1010
<param name="resolution" type="double" value="0.01" />
1111
<param name="base_frame_id" type="string" value="$(arg base_frame_id" />

0 commit comments

Comments
 (0)