ProAut OctoMap

intro_sec

This package was designed to automatically remove outdated voxels from the 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.

node_sec

Our implementation of decay:

rosrun octomap_pa octree_stamped_pa_node
roslaunch octomap_pa octomap_stamped_pa.launch

The native implementation of decay by the original octomap package:

rosrun octomap_pa octree_stamped_native_node
roslaunch octomap_pa octomap_stamped_native.launch

Simple node without decay:

rosrun octomap_pa octree_pa_node
roslaunch octomap_pa octomap_pa.launch

Input and Output Topics:

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).

Services:

Service Name | Type | Description -------------------|----------------------------------------------------------------------------------------------------------------------------|--------------------------------- "~/clear" | std_srvs/Empty | Deletes internal octomap. "~/getsize" | octomap_pa/OctomapPaGetSize | Returning number of nodes, total size in bytes and number of inserted measurments. "~/save" | octomap_pa/OctomapPaFileName | Storing the current octomap as file - timestamps are not saved. "~/load" | octomap_pa/OctomapPaFileName | Loading a octomap from file - timestamps are ignored.

Parameters:

degrading of voxels 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.

pointcloud insertion 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.

octomap in general 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.

topics and services 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.

links_sec

Source code at github: + https://github.com/TUC-ProAut/ros_octomap

Related packages: + https://github.com/TUC-ProAut/ros_parameter

ROS packages: + ros-kinetic-octomap-pa + packages for indigo and lunar will be soon available

doc_sec

ROS-Distribution | Documentation --------------------|--------------- Indigo | docs.ros.org Jade (EOL May 2017) | - Kinetic | docs.ros.org Lunar | docs.ros.org



octomap_pa
Author(s):
autogenerated on Thu Jun 6 2019 17:53:30