This package was designed to automatically remove outdated voxels from the original octomap.
We described our motivation and concept on our octomap-website - here you will also find two supportive videos. For further explanations, you may want to have a look at this workshop abstract.
Our implementation of decay:
The native implementation of decay by the original octomap package:
Simple node without decay:
| Topic Name | Type | Description |
|---|---|---|
| "~/in_cloud" | sensor_msgs/PointCloud2 | Input as new pointcloud type. |
| "~/in_cloud_old" | sensor_msgs/PointCloud | Input as old pointloud type. Will be converted to new pointcloud type. |
| "~/in_laser" | sensor_msgs/LaserScan | Input as single laser scan. Will be converted to new pointcloud type by package "laser_geometry". |
| "~/out_octomap" | octomap_msgs/Octomap | Output of binary octomap - voxels are either free or occupied (smaller in size). |
| "~/out_octomap_full" | octomap_msgs/Octomap | Output of octomap (full size). |
| "~/out_cloud_free" | sensor_msgs/PointCloud2 | Output of all free voxels as pointcloud. |
| "~/out_cloud_occupied" | sensor_msgs/PointCloud2 | Output of all occupied voxels as pointcloud. |
All topics can be remapped using parameters (see below).
| Service Name | Type | Description |
|---|---|---|
| "~/clear" | std_srvs/Empty | Deletes internal octomap. |
| "~/reset" | octomap_pa_msgs/Reset | Changes the resolution and the frame after clearing the internal octomap. |
| "~/getsize" | octomap_pa_msgs/GetSize | Returning number of nodes, total size in bytes and number of inserted measurments. |
| "~/save" | octomap_pa_msgs/FileName | Storing the current octomap as file - timestamps are not saved. |
| "~/load" | octomap_pa_msgs/FileName | Loading a octomap from file - timestamps are ignored. |
| Parameter Name | Type | Description |
|---|---|---|
| "~/degrading_time" | double | Duration how long the outdated nodes will be kept. |
| "~/auto_degrading" | bool | Turns on automatic degrading. |
| "~/auto_degrading_intervall" | double | Intervall for automatic degrading. |
| Parameter Name | Type | Description |
|---|---|---|
| "~/map_prob_hit" | double | Probability that a positive measurement relates to a occupied voxel. |
| "~/map_prob_miss" | double | Probability that a negative measurement relates to a occupied voxel. |
| "~/pcd_voxel_active" | bool | Use voxel-filter for pointcloud insertion. |
| "~/pcd_voxel_explicit" | bool | Use pcl-filter instead of octomap-filter. |
| "~/pcd_voxel_explicit_relative_resolution" | double | Relative resolution of pcl-filter. |
| Parameter Name | Type | Description |
|---|---|---|
| "~/output_frame" | string | Coordinate system for insertion and output. |
| "~/map_resolution" | double | Side length of one voxel (in meters). |
| "~/map_prob_threshold" | double | Threshold for binary evaluation of single voxels. |
| "~/map_clamp_min" | double | Lower clamping value of occupancy probability. |
| "~/map_clamp_max" | double | Upper clamping value of occupancy probability. |
| Parameter Name | Type | Description |
|---|---|---|
| "~/topic_in_cloud" | string | Name of input topic for new pointclouds. |
| "~/topic_in_cloud_old" | string | Name of input topic for old pointclouds. |
| "~/topic_in_laser" | string | Name of input topic for laser scans. |
| "~/topic_out_octomap" | string | Name of output topic for binary octomap. |
| "~/topic_out_octomap_full" | string | Name of output topic for full octomap. |
| "~/topic_out_cload_free" | string | Name of output topic for free voxels. |
| "~/topic_out_cloud_occupied" | string | Name of output topic for occupied voxels. |
See also this config file. It contains all parameters and their default value.
https://github.com/TUC-ProAut/ros_octomap
https://github.com/TUC-ProAut/ros_parameter
ros-kinetic-octomap-pa _(eol)_
ros-melodic-octomap-pa _(upcoming)_ \ ros-melodic-octomap-pa-msgs _(upcoming)_ \ ros-melodic-octomap-pa-matlab _(upcoming)_
ros-noetic-octomap-pa _(upcoming)_ \ ros-noetic-octomap-pa-msgs _(upcoming)_ \ ros-noetic-octomap-pa-matlab _(upcoming)_
| ROS-Distribution | Build-Status | Documentation |
|---|---|---|
| Indigo | EOL April 2019 | docs.ros.org/indigo |
| Jade | EOL May 2017 | docs.ros.org/jade |
| Kinetic | EOL April 2021 | docs.ros.org/kinetic |
| Lunar | EOL May 2019 | docs.ros.org/lunar |
| Melodic | docs.ros.org/melodic | |
| Noetic | docs.ros.org/noetic |