Mapping

Overview

A 3D reconstruction system for MAVs using GPU is implemented in our work, which gives strong support of data to the navigation and decision making in motion planning. Maintaining and updating a 3D map and planning with the global map are both computational costly. Moreover, the global map can be erroneous with noise and estimation drift. Therefore, we maintain a local map only that provides obstacles information around current robot location.

An environmental occupancy grid map is generated by updating the stereo camera and 2D Rplidar data with voxel projection method. In our implementation, the depth image is transferred to the point cloud and applied with several filters, such as voxel grid downsampling and range pass-through filters to clean the reduce data size. As the limited field of view of the camera, the 2D Rplidar may also be utilized for more accurate and robust mapping. And then euclidean distance filed (EDF) is constructed through Euclidean Distance Transform (EDT).

Our occupancy grid map is built with voxel projection method. Different from the traditional ray casting method, which reprojects the pixel from depth image to correspondent depth voxel, the voxel projection method divides voxel space to scanlines and projects voxels in space to the image plane. The latter approach is faster. More information please refer to our internal report.

Map in simulation testing

Map in real flight testing


Usage

Installation

Refer to System Overview page. The edt repository is for stereo depth mapping.

Nodes

Put the following section in your launch file:

    <include file="$(find edt)/launch/edt_ddrone.launch" >
	    <arg name="system_id" value="$(arg system_id)"/>
    </include>

Remember to set the system_id and topic remap in the launch file correctly.

edt_node

Subscribed topics

  • /revised_sensor/image (sensor_msgs/Image)

    Depth map from stereo camera.

  • /zed/confidence/confidence_map (sensor_msgs/Image)

    Confidence map of the depth.

  • /mavros/position/local (geometry_msgs/PoseStamped)

    UAV current pose

  • /scan (sensor_msgs::LaserScan)

    Laser info

Published topics

  • cost_map (edt::CostMap)

    Cost map used for planning

  • points3 (pcl::PointCloudpcl::PointXYZ)

    Point cloud

Yu Zhou
Yu Zhou
Associate Scientist @Temasek Laboratories

My research interests lie in 3D visual perception and navigation, applied machine learning and autonomous systems!