Cross View SLAM

Overview

Cross View SLAM

This is the associated code and dataset repository for our paper

I. D. Miller et al., "Any Way You Look at It: Semantic Crossview Localization and Mapping With LiDAR," in IEEE Robotics and Automation Letters, vol. 6, no. 2, pp. 2397-2404, April 2021, doi: 10.1109/LRA.2021.3061332.

See also our accompanying video

XView demo video

Compilation

We release the localization portion of the system, which can be integrated with a LiDAR-based mapper of the user's choice. The system reqires ROS and should be built as a catkin package. We have tested with ROS Melodic and Ubuntu 18.04. Note that we require GCC 9 or greater as well as Intel TBB.

Datasets

Our datasets

We release our own datasets from around University City in Philadelphia and Morgantown, PA. They can be downloaded here. Ucity2 was taken several months after Ucity, and both follow the same path. These datasets are in rosbag format, including the following topics:

  • /lidar_rgb_calib/painted_pc is the semantically labelled motion-compensated pointcloud. Classes are encoded as a per-point color, with each channel equal to the class ID. Classes are based off of cityscapes and listed below.
  • /os1_cloud_node/imu is raw IMU data from the Ouster OS1-64.
  • /quad/front/image_color/compressed is a compressed RGB image from the forward-facing camera.
  • /subt/global_pose is the global pose estimate from UPSLAM.
  • /subt/integrated_pose is the integrated pose estimate from UPSLAM. This differs from the above in that it does not take into account loop closures, and is used as the motion prior for the localization filter.

Please note that UPSLAM odometry was generated purely based on LiDAR without semantics, and is provided to act as a loose motion prior. It should not be used as ground truth.

If you require access to the raw data for your work, please reach out directly at iandm (at) seas (dot) upenn (dot) edu.

KITTI

We provide a derivative of the excellent kitti2bag tool in the scripts directory, modified to use semantics from SemanticKITTI. To use this tool, you will need to download the raw synced + rectified data from KITTI as well as the SemanticKITTI data. Your final directory structure should look like

2011-09-30
  2011_09_30_drive_0033_sync  
    image_00
      timestamps.txt
      data
    image_01
      timestamps.txt
      data
    image_02
      timestamps.txt
      data
    image_03
      timestamps.txt
      data
    labels
      000000.label
      000001.label
      ...
    oxts
      dataformat.txt
      timestamps.txt
      data
    velodyne_points
      timestamps_end.txt  
      timestamps_start.txt
      timestamps.txt
      data
  calib_cam_to_cam.txt  
  calib_imu_to_velo.txt  
  calib_velo_to_cam.txt

You can then run ./kitti2bag.py -t 2011_09_30 -r 0033 raw_synced /path/to/kitti in order to generate a rosbag usable with our system.

Classes

Class Label
2 Building
7 Vegetation
13 Vehicle
100 Road/Parking Lot
102 Ground/Sidewalk
255 Unlabelled

Usage

We provide a launch file for KITTI and for our datasets. To run, simply launch the appropriate launch file and play the bag. Note that when data has been modified, the system will take several minutes to regenerate the processed map TDF. Once this has been done once, and parameters are not changed, it will be cached. The system startup should look along the lines of

[ INFO] [1616266360.083650372]: Found cache, checking if parameters have changed
[ INFO] [1616266360.084357050]: No cache found, loading raster map
[ INFO] [1616266360.489371763]: Computing distance maps...
[ INFO] [1616266360.489428570]: maps generated
[ INFO] [1616266360.597603324]: transforming coord
[ INFO] [1616266360.641200529]: coord rotated
[ INFO] [1616266360.724551466]: Sample grid generated
[ INFO] [1616266385.379985385]: class 0 complete
[ INFO] [1616266439.390797168]: class 1 complete
[ INFO] [1616266532.004976919]: class 2 complete
[ INFO] [1616266573.041695479]: class 3 complete
[ INFO] [1616266605.901935236]: class 4 complete
[ INFO] [1616266700.533124618]: class 5 complete
[ INFO] [1616266700.537600570]: Rasterization complete
[ INFO] [1616266700.633949062]: maps generated
[ INFO] [1616266700.633990791]: transforming coord
[ INFO] [1616266700.634004336]: coord rotated
[ INFO] [1616266700.634596830]: maps generated
[ INFO] [1616266700.634608101]: transforming coord
[ INFO] [1616266700.634618110]: coord rotated
[ INFO] [1616266700.634666000]: Initializing particles...
[ INFO] [1616266700.710166543]: Particles initialized
[ INFO] [1616266700.745398596]: Setup complete

ROS Topics

  • /cross_view_slam/gt_pose Input, takes in ground truth localization if provided to draw on the map. Not used.
  • /cross_view_slam/pc Input, the pointwise-labelled pointcloud
  • /cross_view_slam/motion_prior Input, the prior odometry (from some LiDAR odometry system)
  • /cross_view_slam/map Output image of map with particles
  • /cross_view_slam/scan Output image visualization of flattened polar LiDAR scan
  • /cross_view_slam/pose_est Estimated pose of the robot with uncertainty, not published until convergence
  • /cross_view_slam/scale Estimated scale of the map in px/m, not published until convergence

ROS Parameters

  • raster_res Resolution to rasterize the svg at. 1 is typically fine.
  • use_raster Load the map svg or raster images. If the map svg is loaded, raster images are automatically generated in the accompanying folder.
  • map_path Path to map file.
  • svg_res Resolution of the map in px/m. If not specified, the localizer will try to estimate.
  • svg_origin_x Origin of the map in pixel coordinates, x value. Used only for ground truth visualization
  • svg_origin_y Origin of the map in pixel coordinates, y value.
  • use_motion_prior If true, use the provided motion estimate. Otherwise, use 0 velocity prior.
  • num_particles Number of particles to use in the filter.
  • filter_pos_cov Motion prior uncertainty in position.
  • filter_theta_cov Motion prior uncertainty in bearing.
  • filter_regularization Gamma in the paper, see for more details.

Citation

If you find this work or datasets helpful, please cite

@ARTICLE{9361130,
author={I. D. {Miller} and A. {Cowley} and R. {Konkimalla} and S. S. {Shivakumar} and T. {Nguyen} and T. {Smith} and C. J. {Taylor} and V. {Kumar}},
journal={IEEE Robotics and Automation Letters},
title={Any Way You Look at It: Semantic Crossview Localization and Mapping With LiDAR},
year={2021},
volume={6},
number={2},
pages={2397-2404},
doi={10.1109/LRA.2021.3061332}}
Comments
  • satelitte semantic maps

    satelitte semantic maps

    Hi. Awesome work, thank you for open sourcing it! Would you mind explaining how did you get the semantic labels for the google map images? Can you share the KITTI maps for training? Thank you

    opened by melhousni 6
  • Unable to get any meaningful output

    Unable to get any meaningful output

    Thank you for open sourcing your amazing work, I was trying to implement the algorithm on the provided ucity and morgantown datasets on Ubuntu 20, ROS Noetic, the package compiles without any errors however there is nothing visible on rviz even after cycling through the entire rosbag.

    The terminal shows the following output:

    [ INFO] [1669884020.240457438]: No cache found, Loading vector map /home/user/cross_view_ws/src/cross_view_slam/maps/ucity.svg
    [ INFO] [1669884020.274196317]: Map loaded.
    [ INFO] [1669884020.274230856]: Size: 2064 x 1056
    [ INFO] [1669884020.274264123]: Rasterizing map...
    [ INFO] [1669884020.290079826]: Rasterized map size: 2064 x 1056
    [ INFO] [1669884020.290180726]: maps generated
    [ INFO] [1669884020.533160155]: transforming coord
    [ INFO] [1669884022.705918658]: coord rotated
    

    Both the topics

    /cross_view_slam/scan
    /cross_view_slam/map
    

    Don't seem to be publishing anything.

    There are no errors thrown by the program during compilation or while running. And the topic /lidar_rgb_calib/painted_pc shows the following output: Screenshot from 2022-12-01 15-38-56

    Am I missing something here?

    opened by Mnzs1701 4
  • Unable to compile package correctly

    Unable to compile package correctly

    Hello, Great work, thanks for sharing! I haven't been able to compile the package correctly. I get the following error when using catkin_make

    /home/dev/catkin_ws/src/cross_view_slam/src/state_particle.cpp:58:51: error: non-constant-expression cannot be narrowed from type 'double' to 'std::normal_distribution::result_type' (aka 'float') in initializer list [-Wc++11-narrowing] std::normal_distribution scale_dist{1, std::min(2./dist, 0.02)}; ^~~~~~~~~~~~~~~~~~~~~~~ /home/dev/catkin_ws/src/cross_view_slam/src/state_particle.cpp:58:51: note: insert an explicit cast to silence this issue std::normal_distribution scale_dist{1, std::min(2./dist, 0.02)}; ^~~~~~~~~~~~~~~~~~~~~~~ static_cast<result_type>( ) 1 error generated. make[2]: *** [CMakeFiles/cross_view_slam.dir/src/state_particle.cpp.o] Error 1 make[1]: *** [CMakeFiles/cross_view_slam.dir/all] Error 2 make: *** [all] Error 2

    I am using Ubuntu 18.04, ROS melodic, GCC 9.4.0 and TBB 2019. Any idea how to fix this? Thanks

    opened by devdevKBB 2
  • About visualization

    About visualization

    I am very appreciate for your work.

    I am very curious about how to project the 3D point cloud onto the satellite map in your video?

    In addition, did you use rviz during your research? If so, can you provide your rviz configuration file?

    opened by qiaozhijian 1
  • Which sequence of KITTI you choose in your example of README?

    Which sequence of KITTI you choose in your example of README?

    Should I put sequence 00's labels into 2011_09_30_drive_0033_sync? or other sequence? By the way, semantic kitti releases the labels of odometry. However, you use raw data. Is alignment done in your script?

    opened by qiaozhijian 1
Owner
Ian D. Miller
Currently a PhD student at Penn in Electrical and Systems Engineering under Prof. Vijay Kumar.
Ian D. Miller
[CVPR'21] Projecting Your View Attentively: Monocular Road Scene Layout Estimation via Cross-view Transformation

Projecting Your View Attentively: Monocular Road Scene Layout Estimation via Cross-view Transformation Weixiang Yang, Qi Li, Wenxi Liu, Yuanlong Yu, Y

null 118 Dec 26, 2022
PaddleRobotics is an open-source algorithm library for robots based on Paddle, including open-source parts such as human-robot interaction, complex motion control, environment perception, SLAM positioning, and navigation.

简体中文 | English PaddleRobotics paddleRobotics是基于paddle的机器人开源算法库集,包括人机交互、复杂运动控制、环境感知、slam定位导航等开源算法部分。 人机交互 主动多模交互技术TFVT-HRI 主动多模交互技术是通过视觉、语音、触摸传感器等输入机器人

null 185 Dec 26, 2022
A list of papers about point cloud based place recognition, also known as loop closure detection in SLAM (processing)

A list of papers about point cloud based place recognition, also known as loop closure detection in SLAM (processing)

Xin Kong 17 May 16, 2021
A 3D Dense mapping backend library of SLAM based on taichi-Lang designed for the aerial swarm.

TaichiSLAM This project is a 3D Dense mapping backend library of SLAM based Taichi-Lang, designed for the aerial swarm. Intro Taichi is an efficient d

XuHao 230 Dec 19, 2022
FLVIS: Feedback Loop Based Visual Initial SLAM

FLVIS Feedback Loop Based Visual Inertial SLAM 1-Video EuRoC DataSet MH_05 Handheld Test in Lab FlVIS on UAV Platform 2-Relevent Publication: Under Re

UAV Lab - HKPolyU 182 Dec 4, 2022
This package is for running the semantic SLAM algorithm using extracted planar surfaces from the received detection

Semantic SLAM This package can perform optimization of pose estimated from VO/VIO methods which tend to drift over time. It uses planar surfaces extra

Hriday Bavle 125 Dec 2, 2022
A Planar RGB-D SLAM which utilizes Manhattan World structure to provide optimal camera pose trajectory while also providing a sparse reconstruction containing points, lines and planes, and a dense surfel-based reconstruction.

ManhattanSLAM Authors: Raza Yunus, Yanyan Li and Federico Tombari ManhattanSLAM is a real-time SLAM library for RGB-D cameras that computes the camera

null 117 Dec 28, 2022
COVINS -- A Framework for Collaborative Visual-Inertial SLAM and Multi-Agent 3D Mapping

COVINS -- A Framework for Collaborative Visual-Inertial SLAM and Multi-Agent 3D Mapping Version 1.0 COVINS is an accurate, scalable, and versatile vis

ETHZ V4RL 183 Dec 27, 2022
SuMa++: Efficient LiDAR-based Semantic SLAM (Chen et al IROS 2019)

SuMa++: Efficient LiDAR-based Semantic SLAM This repository contains the implementation of SuMa++, which generates semantic maps only using three-dime

Photogrammetry & Robotics Bonn 701 Dec 30, 2022
Real-Time SLAM for Monocular, Stereo and RGB-D Cameras, with Loop Detection and Relocalization Capabilities

ORB-SLAM2 Authors: Raul Mur-Artal, Juan D. Tardos, J. M. M. Montiel and Dorian Galvez-Lopez (DBoW2) 13 Jan 2017: OpenCV 3 and Eigen 3.3 are now suppor

Raul Mur-Artal 7.8k Dec 30, 2022
🛠️ SLAMcore SLAM Utilities

slamcore_utils Description This repo contains the slamcore-setup-dataset script. It can be used for installing a sample dataset for offline testing an

SLAMcore 7 Aug 4, 2022
Official page of Struct-MDC (RA-L'22 with IROS'22 option); Depth completion from Visual-SLAM using point & line features

Struct-MDC (click the above buttons for redirection!) Official page of "Struct-MDC: Mesh-Refined Unsupervised Depth Completion Leveraging Structural R

Urban Robotics Lab. @ KAIST 37 Dec 22, 2022
Symmetry and Uncertainty-Aware Object SLAM for 6DoF Object Pose Estimation

SUO-SLAM This repository hosts the code for our CVPR 2022 paper "Symmetry and Uncertainty-Aware Object SLAM for 6DoF Object Pose Estimation". ArXiv li

Robot Perception & Navigation Group (RPNG) 97 Jan 3, 2023
PanopticBEV - Bird's-Eye-View Panoptic Segmentation Using Monocular Frontal View Images

Bird's-Eye-View Panoptic Segmentation Using Monocular Frontal View Images This r

null 63 Dec 16, 2022
Pytorch implementation of Each Part Matters: Local Patterns Facilitate Cross-view Geo-localization https://arxiv.org/abs/2008.11646

[TCSVT] Each Part Matters: Local Patterns Facilitate Cross-view Geo-localization LPN [Paper] NEWs Prerequisites Python 3.6 GPU Memory >= 8G Numpy > 1.

null 46 Dec 14, 2022
《Where am I looking at? Joint Location and Orientation Estimation by Cross-View Matching》(CVPR 2020)

This contains the codes for cross-view geo-localization method described in: Where am I looking at? Joint Location and Orientation Estimation by Cross-View Matching, CVPR2020.

null 41 Oct 27, 2022
This is the official implementation of 3D-CVF: Generating Joint Camera and LiDAR Features Using Cross-View Spatial Feature Fusion for 3D Object Detection, built on SECOND.

3D-CVF This is the official implementation of 3D-CVF: Generating Joint Camera and LiDAR Features Using Cross-View Spatial Feature Fusion for 3D Object

YecheolKim 97 Dec 20, 2022
Paper: Cross-View Kernel Similarity Metric Learning Using Pairwise Constraints for Person Re-identification

Cross-View Kernel Similarity Metric Learning Using Pairwise Constraints for Person Re-identification T M Feroz Ali, Subhasis Chaudhuri, ICVGIP-20-21

T M Feroz Ali 3 Jun 17, 2022
Joint Versus Independent Multiview Hashing for Cross-View Retrieval[J] (IEEE TCYB 2021, PyTorch Code)

Thanks to the low storage cost and high query speed, cross-view hashing (CVH) has been successfully used for similarity search in multimedia retrieval. However, most existing CVH methods use all views to learn a common Hamming space, thus making it difficult to handle the data with increasing views or a large number of views.

null 4 Nov 19, 2022