This package is for running the semantic SLAM algorithm using extracted planar surfaces from the received detection

Overview

Semantic SLAM

This package can perform optimization of pose estimated from VO/VIO methods which tend to drift over time. It uses planar surfaces extracted from object detections in order to create a sparse semantic map of the environment, thus optimizing the drift of the VO/VIO algorithms.

In order to run this package you will need two additional modules

Currently it can extract planar surfaces and create a semantic map from from the following objects:

  • chair
  • tvmonitor
  • book
  • keyboard
  • laptop
  • bucket
  • car

Related Paper:

@ARTICLE{9045978,
  author={Bavle, Hriday and De La Puente, Paloma and How, Jonathan P. and Campoy, Pascual},
  journal={IEEE Access}, 
  title={VPS-SLAM: Visual Planar Semantic SLAM for Aerial Robotic Systems}, 
  year={2020},
  volume={8},
  number={},
  pages={60704-60718},
  doi={10.1109/ACCESS.2020.2983121}}

Video

Semantic SLAM

How do I set it up?

First install g2o following these instructions (Tested on Kinetic and Melodic Distributions):

- sudo apt-get install ros-$ROS_DISTRO-libg2o
- sudo cp -r /opt/ros/$ROS_DISTRO/lib/libg2o_* /usr/local/lib
- sudo cp -r /opt/ros/$ROS_DISTRO/include/g2o /usr/local/include

Install OctopMap server for map generation capabilities:

- sudo apt install ros-$ROS_DISTRO-octomap*

Try a simple example with pre-recorded VIO pose and a blue bucket detector:

Create a ros workspace and clone the following packages:

  • Download the rosbag:
    wget -P ~/Downloads/ https://www.dropbox.com/s/jnywuvcn2m9ubu2/entire_lab_3_rounds.bag
  • Create a workspace, clone the repo and compile:
    mkdir -p workspace/ros/semantic_slam_ws/src/ && cd workspace/ros/semantic_slam_ws/src/    
    git clone https://github.com/hridaybavle/semantic_slam && git clone https://bitbucket.org/hridaybavle/bucket_detector.git   
    cd .. && catkin build --cmake-args -DCMAKE_BUILD_TYPE=Release
  • Launch and visualize
    source devel/setup.bash
    roslaunch semantic_SLAM ps_slam_with_snap_pose_bucket_det_lab_data_with_octomap.launch bagfile:=${HOME}/Downloads/entire_lab_3_rounds.bag show_rviz:=true  

test

Using Docker Image

If the code is giving problems with you local machine, you can try the docker image created with the repo and the required settings.

Download Docker from: Docker

Follow the commands to run the algorithm with the docker

  docker pull hridaybavle/semantic_slam:v1 	
  docker run --rm -it --net="host" -p 11311:11311 hridaybavle/semantic_slam:v1 bash
  cd ~/workspace/ros/semantic_slam_ws/
  source devel/setup.bash
  roslaunch semantic_SLAM ps_slam_with_snap_pose_bucket_det_lab_data_with_octomap.launch bagfile:=${HOME}/Downloads/entire_lab_3_rounds.bag show_rviz:=false  

Open a new terminal and rviz in local machine

  cd ~/Downloads/ && wget https://raw.githubusercontent.com/hridaybavle/semantic_slam/master/rviz/graph_semantic_slam.rviz
  rviz -d graph_semantic_slam.rviz	

Subsribed Topics

Published Topics

The configurations of the algorithms can be found inside the cfg folder in order to be changed accordingly.

Published TFs

  • map to odom transform: The transform published between the map frame and the odom frame after the corrections from the semantic SLAM.

  • base_link to odom transform: The transform published between the base_link (on the robot) frame and the odom frame as estimated by the VO/VIO algorithm.

You might also like...
Indoor Panorama Planar 3D Reconstruction via Divide and Conquer
Indoor Panorama Planar 3D Reconstruction via Divide and Conquer

HV-plane reconstruction from a single 360 image Code for our paper in CVPR 2021: Indoor Panorama Planar 3D Reconstruction via Divide and Conquer (pape

[ICCV 2021 (oral)] Planar Surface Reconstruction from Sparse Views
[ICCV 2021 (oral)] Planar Surface Reconstruction from Sparse Views

Planar Surface Reconstruction From Sparse Views Linyi Jin, Shengyi Qian, Andrew Owens, David F. Fouhey University of Michigan ICCV 2021 (Oral) This re

PyTorch implementation of HDN(Homography Decomposition Networks) for planar object tracking
PyTorch implementation of HDN(Homography Decomposition Networks) for planar object tracking

Homography Decomposition Networks for Planar Object Tracking This project is the offical PyTorch implementation of HDN(Homography Decomposition Networ

Pytorch implementation of paper:
Pytorch implementation of paper: "NeurMiPs: Neural Mixture of Planar Experts for View Synthesis"

NeurMips: Neural Mixture of Planar Experts for View Synthesis This is the official repo for PyTorch implementation of paper "NeurMips: Neural Mixture

Sequence lineage information extracted from RKI sequence data repo
Sequence lineage information extracted from RKI sequence data repo

Pango lineage information for German SARS-CoV-2 sequences This repository contains a join of the metadata and pango lineage tables of all German SARS-

Official page of Struct-MDC (RA-L'22 with IROS'22 option); Depth completion from Visual-SLAM using point & line features
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

Code for
Code for "Diffusion is All You Need for Learning on Surfaces"

Source code for "Diffusion is All You Need for Learning on Surfaces", by Nicholas Sharp Souhaib Attaiki Keenan Crane Maks Ovsjanikov NOTE: the linked

Code for Iso-Points: Optimizing Neural Implicit Surfaces with Hybrid Representations
Code for Iso-Points: Optimizing Neural Implicit Surfaces with Hybrid Representations

Implementation for Iso-Points (CVPR 2021) Official code for paper Iso-Points: Optimizing Neural Implicit Surfaces with Hybrid Representations paper |

 Neural-Pull: Learning Signed Distance Functions from Point Clouds by Learning to Pull Space onto Surfaces(ICML 2021)
Neural-Pull: Learning Signed Distance Functions from Point Clouds by Learning to Pull Space onto Surfaces(ICML 2021)

Neural-Pull: Learning Signed Distance Functions from Point Clouds by Learning to Pull Space onto Surfaces(ICML 2021) This repository contains the code

Comments
  • errors at last step

    errors at last step

    Hi, I have finished all the steps following the instructions and nothing goes wrong. But when I run

    roslaunch semantic_SLAM ps_slam_with_snap_pose_bucket_det_lab_data.launch bagfile:=${HOME}/Downloads/entire_lab_3_rounds.bag show_rviz:=true  
    

    I get errors like this and it stucks for a while.

    # Using CSparse poseDim -1 landMarkDim -1 blockordering 0
    done
    keyframe_delta_trans 0.5
    keyframe_delta_angle 0.5
    keyframe_delta_time 1
    use_const_inf_matrix: 1
    const_stddev_x: 0.00667
    const_stddev_q: 1e-05
    Initialized mapping thread 
    camera angle in radians: 0.59219
    update keyframe every detection: 1
    add first landmark: 0
    [semantic_graph_slam_node-9] process has died [pid 23067, exit code -11, cmd /home/nrc/workspace/ros/semantic_slam_ws/devel/lib/semantic_SLAM/semantic_graph_SLAM_node __name:=semantic_graph_slam_node __log:=/home/nrc/.ros/log/ccaf4b14-a47a-11ea-b300-000c29c39525/semantic_graph_slam_node-9.log].
    log file: /home/nrc/.ros/log/ccaf4b14-a47a-11ea-b300-000c29c39525/semantic_graph_slam_node-9*.log
    

    then I get this. It seems that the visualization program doesn't go right.

    [rosbag-2] process has finished cleanly
    log file: /home/nrc/.ros/log/ccaf4b14-a47a-11ea-b300-000c29c39525/rosbag-2*.log
    

    Is there something I have missed? Thank you!

    opened by ZhengXinyue 8
  • [semantic_graph_slam_node-9] process has died

    [semantic_graph_slam_node-9] process has died

    Hi, I have finished all the steps following the instructions and nothing goes wrong. But when I run

    roslaunch semantic_SLAM ps_slam_with_snap_pose_bucket_det_lab_data_with_octomap.launch bagfile:=${HOME}/Downloads/entire_lab_3_rounds.bag show_rviz:=true
    

    I get errors like this.

    done
    keyframe_delta_trans 0.5
    keyframe_delta_angle 0.5
    keyframe_delta_time 1
    use_const_inf_matrix: 1
    const_stddev_x: 0.00667
    const_stddev_q: 1e-05
    camera angle in radians: 0.59219
    update keyframe every detection: 1
    add first landmark: 0
    [ INFO] [1591944956.099907360, 1661396775.076756992]: waitForService: Service [/depth_rectifier_manager/load_nodelet] is now available.
    [ INFO] [1591944956.100243666, 1661396775.076756992]: waitForService: Service [/depth_manager/load_nodelet] is now available.
    [ INFO] [1591944956.545617511, 1661396775.518832629]: Stereo is NOT SUPPORTED
    [ INFO] [1591944956.545842654, 1661396775.518832629]: OpenGl version: 4.5 (GLSL 4.5).
    [pcl::OrganizedNeighbor::radiusSearch] Input dataset is not from a projective device!
    Residual (MSE) 0.000614, using 1248 valid points
    [pcl::OrganizedNeighbor::radiusSearch] Input dataset is not from a projective device!
    Residual (MSE) 0.000748, using 1444 valid points
    [pcl::OrganizedNeighbor::radiusSearch] Input dataset is not from a projective device!
    Residual (MSE) 0.001710, using 2303 valid points
    [semantic_graph_slam_node-9] process has died [pid 27314, exit code -9, cmd /home/nrc/hd/workspace/ros/semantic_slam_ws/devel/lib/semantic_SLAM/semantic_graph_SLAM_node __name:=semantic_graph_slam_node __log:=/home/nrc/.ros/log/c2c4ddd8-ac79-11ea-96ed-8ca982ff1833/semantic_graph_slam_node-9.log].
    log file: /home/nrc/.ros/log/c2c4ddd8-ac79-11ea-96ed-8ca982ff1833/semantic_graph_slam_node-9*.log
    

    When it occurs

    [pcl::OrganizedNeighbor::radiusSearch] Input dataset is not from a projective device!
    Residual (MSE) 0.000614, using 1248 valid points
    

    the program is still mapping , so I think the problem is not caused by 'pcl'.

    I tried to run the launchfile seperately :

    ROS_NAMESPACE=camera/color rosrun image_proc image_proc 
    roslaunch semantic_SLAM shape.launch  
    rosrun semantic_SLAM  semantic_graph_SLAM_node
    

    But at the last step i got 'Segmentation fault :

    add first landmark: 0
    Segmentation fault (core dumped)
    

    Do you have any idea about it? Thanks a lot !!!

    opened by He-Rong 6
  • Dataset download failure problem

    Dataset download failure problem

    Hello, when I run the sample code, I always encounter network interruptions or unknown errors at the last moment when downloading the dataset entire_lab_3_rounds.bag. Can you provide a new way to download the bag?

    opened by kycwx 2
  • Problemas de incompatibilidad de opencv en el bucket detector

    Problemas de incompatibilidad de opencv en el bucket detector

    Hola, he conseguido que ambos paquetes en conjunto (semantic slam y bucket detector) funciones bien en una distro de ubuntu virgen con ROS melodic, sin embargo, cuando migro al pc donde trabajo habitualmente y que tiene ya instaladas dependencias anteriores y demás me encuentro con estos errores referentes a opencv: Captura de pantalla de 2021-05-26 11-29-18 Imagino que se deben a incompatibilidades entre versiones de opencv, podrías confirmarme esto último? Sería posible trabajar con una versión de opencv diferente? Gracias, un saludo!

    opened by iandresolares 2
Releases(2.0.0)
Owner
Hriday Bavle
Postdoctoral Researcher at the University of Luxembourg. My research interests are VO/VIO, SLAM, Perception and Planning applied to Mobile Robots.
Hriday Bavle
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
Genetic Algorithm, Particle Swarm Optimization, Simulated Annealing, Ant Colony Optimization Algorithm,Immune Algorithm, Artificial Fish Swarm Algorithm, Differential Evolution and TSP(Traveling salesman)

scikit-opt Swarm Intelligence in Python (Genetic Algorithm, Particle Swarm Optimization, Simulated Annealing, Ant Colony Algorithm, Immune Algorithm,A

郭飞 3.7k Jan 3, 2023
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
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
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
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
Python implementation of 3D facial mesh exaggeration using the techniques described in the paper: Computational Caricaturization of Surfaces.

Python implementation of 3D facial mesh exaggeration using the techniques described in the paper: Computational Caricaturization of Surfaces.

Wonjong Jang 8 Nov 1, 2022
git《Learning Pairwise Inter-Plane Relations for Piecewise Planar Reconstruction》(ECCV 2020) GitHub:

Learning Pairwise Inter-Plane Relations for Piecewise Planar Reconstruction Code for the ECCV 2020 paper by Yiming Qian and Yasutaka Furukawa Getting

null 37 Dec 4, 2022
Planar Prior Assisted PatchMatch Multi-View Stereo

ACMP [News] The code for ACMH is released!!! [News] The code for ACMM is released!!! About This repository contains the code for the paper Planar Prio

Qingshan Xu 127 Dec 31, 2022
Python and C++ implementation of "MarkerPose: Robust real-time planar target tracking for accurate stereo pose estimation". Accepted at LXCV @ CVPR 2021.

MarkerPose: Robust real-time planar target tracking for accurate stereo pose estimation This is a PyTorch and LibTorch implementation of MarkerPose: a

Jhacson Meza 47 Nov 18, 2022