Accurate and complete terrain maps enhance the awareness of autonomous robots and enable safe and optimal path planning. Rocks and topography often create occlusions and lead to missing elevation information in the Digital Elevation Map (DEM). Currently, mostly traditional inpainting techniques based on diffusion or patch-matching are used by autonomous mobile robots to fill-in incomplete DEMs. These methods cannot leverage the high-level terrain characteristics and the geometric constraints of line of sight we humans use intuitively to predict occluded areas. We propose to use neural networks to reconstruct the occluded areas in DEMs. We introduce a self-supervised learning approach capable of training on real-world data without a need for ground-truth information. We accomplish this by adding artificial occlusion to the incomplete elevation maps constructed on a real robot by performing ray casting. We first evaluate a supervised learning approach on synthetic data for which we have the full ground-truth available and subsequently move to several real-world datasets. These real-world datasets were recorded during autonomous exploration of both structured and unstructured terrain with a legged robot, and additionally in a planetary scenario on Lunar analogue terrain. We state a significant improvement compared to the Telea and Navier-Stokes baseline methods both on synthetic terrain and for the real-world datasets. Our neural network is able to run in real-time on both CPU and GPU with suitable sampling rates for autonomous ground robots.
Our work has been published in the IEEE Robotics and Automation Letters (RA-L). Please refer to the paper on IEEE Xplore or on ArXiv.
We invite you to see our method in action in a video, where we record the inference of our method on the Gonzen mine dataset recorded with the ANYmal C legged robot: https://youtu.be/2Khxeto62LQ
Please cite our paper if you use our method in your work:
@ARTICLE{stolzle2022reconstructing,
author={Stolzle, Maximilian and Miki, Takahiro and Gerdes, Levin and Azkarate, Martin and Hutter, Marco},
journal={IEEE Robotics and Automation Letters},
title={Reconstructing occluded Elevation Information in Terrain Maps with Self-supervised Learning},
year={2022},
volume={7},
number={2},
pages={1697-1704},
doi={10.1109/LRA.2022.3141662}
}
This framework requires > Python 3.9.2. The generation of synthetic datasets requires an Ubuntu environment.
Note: To use efficient neural network training, CUDA 11.* needs to be installed and available.
It is recommended to use a package manager like Conda (https://docs.conda.io/en/latest/) to manage the Python version and all required Python packages.
After setting the environment variable $WORKSPACE
to a folder you want to work in, you should clone this repo:
git clone https://github.com/mstoelzle/solving occlusion $WORKSPACE/solving-occlusion && cd $WORKSPACE/solving-occlusion
All git submodules need to be initialized and updated:
git submodule update --init --recursive
Please install the following C++ dependencies to use this repo:
conda install cmake pybind11 eigen
or alternatively on macOS with homebrew:
brew install cmake pybind11 eigen
or on Ubuntu with:
sudo apt install cmake python-pybind11 libeigen3-dev
On Windows we need to additionally install Visual Studio C++ to build Python packages and subsequently install dlib via pip:
pip install dlib
If we want to leverage a NVIDIA GPU to train and infer the neural network, we need to install PyTorch first using conda:
conda install pytorch=1.8 torchvision=0.9 torchaudio=0.8 cudatoolkit=11.1 -c pytorch -c conda-forge
The required Python packages can be installed as follows (within the Conda environment) in the root directory:
pip install -r ${WORKSPACE}/solving-occlusion/requirements.txt --user
We rely on ROS Noetic to read datasets stored in rosbags and process them in our DatasetGeneration component.
On Ubuntu this can be done with:
sudo apt install ros-noetic-ros-base ros-noetic-grid-map
or on macOS with (requires Python 3.6.* or 3.8.* for now):
conda install -c robostack ros-noetic-ros-base ros-noetic-grid-map
System requirements: Ubuntu >= 16.04, g++ / gcc >= 6, CMake >= 3.10, CPU with support for avx2 instructions (produced within last 6 years)
First, please install RaiSim including its plugins raisimLib and raisimOgre: https://raisim.com/sections/Installation.html. Please acquire the appropriate license.
Initialise the raisim build directory: export LOCAL_INSTALL=$WORKSPACE/raisim_build && mkdir $LOCAL_INSTALL
As the generation of a synthetic dataset relies on the TerrainDataGenerator by Takahiro Miki,
the following installation instruction need to be followed recursively after the src/dataset_generation/synthetic_terrain_data_generator
git submodule is initialised:
https://bitbucket.org/tamiki/terrain_data_generator
After following the installation instructions, the build directory needs to be added to the CMAKE_PREFIX_PATH:
export CMAKE_PREFIX_PATH=$CMAKE_PREFIX_PATH:$LOCAL_INSTALL
Additionally, the terrain_data_generator
submodule has a requirement on OpenCV:
sudo apt-get install libopencv-dev
Finally, install the terrain_data_generator
package:
pip install --user -e "${WORKSPACE}/solving-occlusion/src/dataset_generation/synthetic_terrain_data_generator"
We use the PatchMatch [1] algorithm as a (traditional) baseline for in-painting of the occluded elevation maps.
If this baseline is specified for use in the config, the following installation steps to use the dependency PyPatchMatch need to be taken:
cd "${WORKSPACE}/solving-occlusion/src/learning/models/baseline/py_patch_match" && make
We first need to install the dependencies CMake, OpenCV and PCL. On macOS:
brew install cmake opencv pcl eigen
Subsequently, we can install the Python wrapper for the rock perception-traversability
component with:
pip install git+https://github.com/esa-prl/perception-traversability-pybind.git
We rely on custom pocolog Python bindings to read pocolog logs containing the elevation maps generated by the GA Slam
method on the Tenerife dataset (see Tenerife Dataset).
We rely on an existing Rock installation to build these pocolog python bindings.
Please add the tools-pocolog_pybind repository to your Rock installation in the folder tools/pocolog_pybind
.
Subsequently, we can install the Python wrapper with:
pip install --user /home/user/rock/tools/pocolog_pybind
We use JSON config files to specify all settings and parameters of our experiments.
All config files need to be placed in a subdirectory of {DIR_TO_REPO}/configs
.
Subsequently, a dataset generation can be started by stating the path relative to the {DIR_TO_REPO}
directory:
python dataset_generation.py configs/{CONFIG_NAME}.json
We use JSON config files to specify all settings and parameters of our experiments.
All config files need to be placed in a subdirectory of {DIR_TO_REPO}/configs
.
The absolute or relative path to the dataset needs to be specified in the JSON config.
Subsequently, a learning experiment can be started by stating the path relative to the {DIR_TO_REPO}
directory:
python main.py configs/{CONFIG_NAME}.json
We immediately visualize the trained model after all tasks of an experiment (e.g. seed) have completed as specified in
experiment/visualization
section of the config. That said, you can also visualize an experiment manually.
In this case, please specify the path to the config.json
within the experiment log directory:
python visualization.py {PATH_TO_EXPERIMENT_LOGDIR}/config.json
The main ingredient to path learning are what we call task paths. They consist of different "training regimes" applied sequentially to a machine learning model. In our implementation they create tasks from their configs and are used as iterators to yield these tasks.
A task consists of a set of dataloaders, which are created from a base dataset and transformers applied to it. Moreover it also specifies a loss function, loss aggregator and the batch size for the dataloader. In our implementation tasks measure their own runtime by using the "with" keyword.
The controller is a member of the learning classes. It is implemented as an iterator that yields epochs until convergence or a maximum number of epochs is reached.
The experiment contains all other objects introduced above. It manages device placement and logdir creation.
We evaluate our methods on a dataset which was collected in June 2017 at the "Minas de San José" site in Tenerife using the Heavy Duty Planetary Rover (HDPR) as a Lunar Analogue. This dataset consists of images from three stereo cameras, one of which on a pan tilt unit, LiDAR and a Time of Flight (ToF) camera. It also includes an onboard Inertial Measurements Unit (IMU), an additional laser gyro for heading estimation and Global Navigation Satellite System (GNSS) antenna for ground-truth absolute positioning. The dataset is stored in serialized Rock pocolog logs. We apply the GA SLAM [2] technique on the raw data to extract occluded Digital Elevation Maps (DEMs).
We benchmark or methods on the enav-planetary dataset [3].
We need to project the stitched point clouds stored in the dataset to 2.5D elevation maps.
We use the GridMap ROS package to transform ROS
sensors_msgs/PointCloud2
messages to grid_map_msgs/grid_map
.
- Download rosbag with point clouds from: https://starslab.ca/enav-planetary-dataset/
- Copy grid map PCL config:
cp {PATH_TO_SOLVING_OCCLUSION}/src/ros/configs/grid_map_pcl_params.yml {PATH_TO_GRID_MAP}/grid_map_pcl/parameters.yml
- Generate rosbag with grid map messages from rosbag with point clouds. Run the following three ROS1 commands each in a separate terminal:
Converter ROS node:
roslaunch grid_map_pcl PointCloud2_to_GridMap_msg_node.launch
Save /grid_map
topic to a new rosbag:
rosbag record /grid_map
Replay rosbag with point cloud 2 messages at rate of 1% of original speed:
rosbag play -r 0.01 run1_clouds_only.bag
Generate a synthetic height map dataset:
python dataset_generation.py configs/dg/synthetic_height_map_dataset_generation.json
Train on the synthetic height map terrain using supervised learning (after adjusting the path to the dataset in the config):
python main.py configs/learning/height_map/unet_synthetic_height_map_learning_supervised.json
Generate a HDF5 solving occlusion dataset from a rosbag containing GridMap messages (in this case for ENAV planetary dataset):
python dataset_generation.py configs/dg/enav_planetary.json
Train using self-supervised learning on a real-world solving occlusion HDF5 dataset:
python main.py configs/learning/enav/unet_enav_learning_self_supervision_raycasting_seed_101.json
[1] Barnes, Connelly, et al. "PatchMatch: A randomized correspondence algorithm for structural image editing." ACM Trans. Graph. 28.3 (2009): 24.
[2] Geromichalos, Dimitrios, et al. "SLAM for autonomous planetary rovers with global localization." Journal of Field Robotics 37.5 (2020): 830-847.
[3] Lamarre, Olivier, et al. "The canadian planetary emulation terrain energy-aware rover navigation dataset." The International Journal of Robotics Research 39.6 (2020): 641-650.