Only released in EOL distros:
Package Summary
This package contains two nodes for pole extraction and mapping for aiding 3D climbing robots in navigation and localization.
- Author: Gonçalo Cabrita and Mahmoud Tavakoli
- License: BSD
- Source: svn http://isr-uc-ros-pkg.googlecode.com/svn/stacks/lse_climber_robots/trunk
Contents
Overview
The goal of the software presented in this stack is to be able to use a ground robot equipped with a depth sensor to generate a 3D map of a structure composed of poles as it is climbed by a climbing robot. This sections contains an overview of the two algorithms implemented in this package, pole section extractor and 3D structure mapper.
Pole Extractor
This algorithm is in charge of extracting pole sections from the environment inside a region of interest centered at the gripper of the climbing robot. Extraction is achieved using cylindrical segmentation.
3D Structure Mapper
This algorithm uses the pole sections published by pole extractor to construct a map of the structure being climbed.
For more details on how the algorithms work check the publications section down below.
ROS API
pole_extractor_node
pole_extractor_node is a region of interest cylindrical segmentation algorithm.Subscribed Topics
chewed_cloud (sensor_msgs/PointCloud2)- The point cloud from the depth sensor.
- Control topic for outputting data or not.
Published Topics
pole_cloud (sensor_msgs/PointCloud2)- This allows to visually debug the segmented pole surface.
- This allows to visually debug the filtered roi point cloud.
- This allows to visually debug the output of the algorithm.
- The output of the algorithm.
Parameters
~gripper_tag_frame_id (string, default: ar_marker)- The frame id of the gripper ar tag.
- The width of the roi.
- The height of the roi.
- The minimum diameter admissible for the cylindrical segmentation.
- The maximum diameter admissible for the cylindrical segmentation.
- Normal distance parameter of the cylindrical segmentation.
- Maximum number of iterations for the cylindrical segmentation.
- Distance threshold parameter of the cylindrical segmentation.
structure_mapper_node
structure_mapper_node is a 3D structure mapper for climbing robots.Subscribed Topics
pole (pole_structure_mapper/PoleSectionStamped)- The output of the pole extractor algorithm.
Published Topics
pole_structure (pole_structure_mapper/PoleStructure)- The output of the algorithm.
- This allows to visually debug the output of the algorithm.
Parameters
~global_frame_id (string, default: map)- The global frame id.
- The diameter threshold for matching two pole sections (in meters).
- The axis threshold for matching two pole sections (in degrees).
- The distance threshold for matching two pole sections (in meters).
- The minimum length a pole section must have to be considered.
- The lifespan of a temporary pole section.
- Number of pole sections required to turn a temporary section into a permanent one.
Video
The following video shows the pole extractor and 3D stricture mapper working in rviz.
Tutorials
Coming soon...
Related Publications
Coming soon...