Skip to content

Latest commit

 

History

History
113 lines (62 loc) · 4.97 KB

File metadata and controls

113 lines (62 loc) · 4.97 KB

3D Voxel Map to 2D Occupancy Map Conversion Using Free Space Representation

This package is for ROS2. See the ros branch for the ROS version.

This ROS2 package converts voxel maps generated by the OctoMap mapping solution into 2D occupancy maps for unmanned aerial vehicles (UAVs) and unmanned ground vehicles (UGV). The package also provides a method to convert 2D paths to 3D paths for UAVs and UAVs.

The method uses free space in the voxel map to find navigable space in the voxel map, as well as extracting a height map to create a traversability slope map, which is used to detect obstacles in the environment and include them in the map generated for the UGVs.

The Height map can also be used to convert paths from 2D to 3D using the path_converter_node provided by the package.

Paper and Citation

This ROS2 package is based on the following article:

Voxel Map to Occupancy Map Conversion Using Free Space Projection for Efficient Map Representation for Aerial and Ground Robots [RA-L][ArXiv]

@ARTICLE{10750397,
  author={Fredriksson, Scott and Saradagi, Akshit and Nikolakopoulos, George},
  journal={IEEE Robotics and Automation Letters}, 
  title={Voxel Map to Occupancy Map Conversion Using Free Space Projection for Efficient Map Representation for Aerial and Ground Robots}, 
  year={2024},
  volume={9},
  number={12},
  pages={11625-11632},
  doi={10.1109/LRA.2024.3495575}}

If you use this ROS2 package in a scientific publication, please cite the paper.

Installation

  1. Install OctoMap for ROS2 or $ sudo apt install ros-<ROS2 version>-octomap-server
  2. Navigate to the src folder in the ROS2 workspace cd ~/ros2_ws/src
  3. Clone the GitHub to ROS2 workspace: git clone https://github.com/LTU-RAI/Map-Conversion-3D-Voxel-Map-to-2D-Occupancy-Map.git
  4. cd ..
  5. Build project: colcon build --packages-select mapconversion

ROS2 Launch Files

map_conversion_oct.launch.py: Example launch file for launching map conversion node

path_conversion.launch.py: Example launch file for launching map path conversion node

ROS Nodes

map_conversion_oct_node

A node that converts the input 3D voxel map to a 2D occupancy map and a height map with the height of the floor and ceiling.

Ros Parameters

map_frame: Name of frame map.

map_position_z: Z position used for the outputted 2D maps.

minimum_z: Minimum height of free space the robot can traverse.

max_slope_ugv: Maximum slope ground robot can climb, used to detect and represent obstacles in the 2D occupancy map

slope_estimation_size: Determine the size of the area used to estimate the slope in one cell. The size of the area will be equal to (2*slope_estimation_size+1)².

Subscribed Topics

octomap: Input voxel map.

Published Topics

mapUGV: Map for a ground robot, includes obstacles detected using max_slope_ugv.

mapUAV: Map for aerial robot containing free space and bounding walls.

heightMap: 2D map containing the height of the floor and ceiling of the environment.

slopeMap: 2D map containing the slope value for the floor in the environment.

visualization_floor_map: Rviz cost map, for showing a heat map of the floor height in the heightMap. This is only for visualization.

visualization_ceiling_map: Rviz cost map, for showing a heat map of the ceiling height in the heightMap. This is only for visualization.

visualization_slope_map: Rviz cost map, for showing a heat map of the slope of the map in the range 0 to 2*max_slope_ugv. This is only for visualization.

path_converter_node

A node that converts the input path generated using a 2D planer to a 3D path using heightMap generated by map_conversion_node.

Ros Parameters

use_collision_sphere: Add collision sphere around the robot. Use true for aerial robots and false for ground robots. If a collision with either the floor or ceiling is detected during path conversion, the path will be adjusted so that no collision occurs.

collision_radius: Radius for collision sphere, only used if use_collision_sphere is true.

path_offset: Desired height above ground for the robot.

path_smothing_length: The amount of steps before and after the robot is used for path smoothing.

Subscribed Topics

heightMap: Hight map used for 2D to 3D conversion generated by map_conversion_node.

pathIn: 2D path that will be converted into 3D.

Published Topics

pathOut: 3D path converted from 2D using the heightMap.