Skip to content

ChanJoon/exploration-algorithms

 
 

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

29 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

Exploration-algorithms

  • How to build, install and run open-source exploration algorithms
  • The repo provides ready-to-go Docker image
  • Algorithms are:
    • NBVP - Receding Horizon "Next-Best-View" Planner for 3D Exploration
    • GBP - Graph-based Path Planning for Autonomous Robotic Exploration in Subterranean Environments
    • GBP2 - Autonomous Teamed Exploration of Subterranean Environments using Legged and Aerial Robots
    • MBP - Motion Primitives-based Path Planning for Fast and Agile Exploration using Aerial Robots
    • AEP - Efficient Autonomous Exploration Planning of Large-Scale 3-D Environments
    • UFOExplorer - UFOExplorer: Fast and Scalable Sampling-Based Exploration With a Graph-Based Planning Structure
    • FUEL - FUEL: Fast UAV Exploration Using Incremental Frontier Structure and Hierarchical Planning
    • DSVP - DSVP: Dual-Stage Viewpoint Planner for Rapid Exploration by Dynamic Expansion
    • TARE - TARE: A Hierarchical Framework for Efficiently Exploring Complex 3D Environments
    • RHEM - Uncertainty-aware receding horizon exploration and mapping using aerial robots
    • GLocal - A Unified Approach for Autonomous Volumetric Exploration of Large Scale Environments Under Severe Odometry Drift
    • OIPP - An Efficient Sampling-Based Method for Online Informative Path Planning in Unknown Environments
    • PredRecon - PredRecon: A Prediction-boosted Planning Framework for Fast and High-quality Autonomous Aerial Reconstruction
    • ERRT - A Tree-based Next-best-trajectory Method for 3D UAV Exploration

List

1. Volumetric mapping purpose only

Name Papers Videos Code Main Group
NBVP 2016 ICRA git ETHZ-ASL
GBP 2019 IROS, 2020 JFR youtube, youtube2, youtube3 Same with GBP2 ETHZ-ASL+RSL / NTNU-ARL
GBP2 2022 ICRA youtube git ETHZ-ASL+RSL / NTNU-ARL
MBP 2020 ICRA youtube, youtube2, youtube3 git ETHZ-ASL / NTNU-ARL
AEP 2019 RAL youtube git LiU-AIICS / KTH-RPL
UFOExplorer 2022 RAL youtube git KTH-RPL
FUEL 2021 RAL youtube git HKUST Aerial Robotics Group
DSVP 2021 IROS youtube git CMU Robotics Institute
TARE 2021 RSS, 2021 ICRA youtube git CMU Robotics Institute
ERRT 2024 T-RO youtube git LTU-RAI

2. Volumetric mapping + Considering pose estimation

Name Papers Videos Code Main Group
RHEM 2017 ICRA, 2019 Autonomous Robots youtube, youtube2 git NTNU-ARL
GLocal 2021 RAL youtube git ETHZ-ASL

3. Volumetric mapping + inspection/coverage path planning

Name Papers Videos Code Main Group
OIPP 2020 RAL youtube git ETHZ-ASL
PredRecon 2023 ICRA (arXiv yet) youtube git HKUST Aerial Robotics Group

Option1: How to build and run with the ready-to-go docker image

Installation

0. Install docker, get image, and generate container

Unfold to see
  • If you do not have docker yet, install it

    curl -fsSL https://get.docker.com/ | sudo sh
    sudo usermod -aG docker $USER
    
    ##### NVIDIA-Docker, GPU
    distribution=$(. /etc/os-release;echo $ID$VERSION_ID) \
       && curl -s -L https://nvidia.github.io/nvidia-docker/gpgkey | sudo apt-key add - \
       && curl -s -L https://nvidia.github.io/nvidia-docker/$distribution/nvidia-docker.list | sudo tee /etc/apt/sources.list.d/nvidia-docker.list
    
    sudo apt-get update
    sudo apt-get install -y nvidia-docker2
    sudo systemctl restart docker
  • Get the ready-to-go docker image with dockerfile

    • make dockerfile with the contents:
      FROM ghcr.io/engcang/exploration_sota:v1.0
      
      # nvidia-container-runtime
      ENV NVIDIA_VISIBLE_DEVICES \
          ${NVIDIA_VISIBLE_DEVICES:-all}
      ENV NVIDIA_DRIVER_CAPABILITIES \
          ${NVIDIA_DRIVER_CAPABILITIES:+$NVIDIA_DRIVER_CAPABILITIES,}graphics
      
      USER ubuntu
      WORKDIR /home/ubuntu
      CMD /bin/bash
    • Then, make the image with docker build -t exploration .
  • Generate a docker conatiner with run.sh file

    • make run.sh with the contents:
      #!/bin/sh
      
      XSOCK=/tmp/.X11-unix
      XAUTH=/tmp/.docker.xauth
      touch $XAUTH
      xauth nlist $DISPLAY | sed -e 's/^..../ffff/' | xauth -f $XAUTH nmerge -
      
      docker run --runtime=nvidia --privileged --gpus all --rm -it \
                 --volume=$XSOCK:$XSOCK:rw \
                 --volume=$XAUTH:$XAUTH:rw \
                 --volume=$HOME:$HOME \
                 --shm-size=4gb \
                 --env="XAUTHORITY=${XAUTH}" \
                 --env="DISPLAY=${DISPLAY}" \
                 --env=TERM=xterm-256color \
                 --env=QT_X11_NO_MITSHM=1 \
                 --net=host \
                 exploration:latest
                 bash
    • Then run container as follows:
      chmod +x run.sh
      ./run.sh

1. How to run

Unfold to see
  • In the docker,
    cd ~/
    ls #see .sh files there
    
    # NBVP
    ./nbvp.sh
    
    # GBP
    ./gbp.sh
    !!Then, click "Start planner" in Rviz
    
    # MBP
    ./mbp.sh
    !!Then, click "Start planner" in Rviz
    
    # AEP
    ./aep_gazebo.sh
    ./aep.sh lidar #with lidar sensor
    ./aep.sh rgbd #with rgbd sensor
    rosservice call /mavros/cmd/arming "value: true"
    rosservice call /mavros/set_mode "base_mode: 0 custom_mode: 'OFFBOARD'"
    
    # FUEL
    ./fuel.sh
    !!Start with "2D Nav Goal" in Rviz
    
    # DSVP
    ./dsvp_tare_sim.sh
    ./dsvp.sh
    
    # TARE
    ./dsvp_tare_sim.sh
    ./tare.sh
    
    # OIPP
    ./oipp.sh
    rosservice call /planner/planner_node/toggle_running "data: true"



Option2: How to build and run on your local computer

Installation

0. Common dependencies

  • ROS: all
  • OctoMap: NBVP, GBP, MBP, AEP, DSVP
  • Voxblox: MBP, GBP, OIPP

1. Install simulator (required)

Unfold to see

Note: When having PX4-SITL and RotorS Simulator at the same time

  • They both use libmav_msgs.so file with the same name but different source codes.
  • If you have both simulators, do not forget to change the name of either one temporally.
    • PX4-SITL: PX4-Autopilot/build/px4_sitl_default/build_gazebo/libmav_msgs.so
    • RotorS: <workspace>/build/rotors_gazebo_plugins/libmav_msgs.so

1-1. Install PX4-SITL - for AEP

1-2. Install RotorS Simulator - for NBVP, GBP, MBP, OIPP, ERRT

  • Because of the version issuse, I recommend to install as here
  • Get the code and build
    cd ~/catkin_ws/src
    git clone https://github.com/ethz-asl/glog_catkin.git
    git clone https://github.com/ethz-asl/rotors_simulator --recursive
    rm -r rotors_simulator/rotors_description
    rm -r rotors_simulator/rotors_gazebo
    
    cd ~/catkin_ws
    git clone https://github.com/engcang/exploration-algorithms
    mv exploration-algorithms/rotors_description src/rotors_simulator/
    mv exploration-algorithms/rotors_gazebo src/rotors_simulator/
    
    catkin build -DCMAKE_BUILD_TYPE=Release

1-3. Install Autonomous Exploration Development Environment - for DSVP, TARE

2. Install algorithms

Note: When having NBVP, GBP, MBP at the same time

  • They use different versions of volumetric_mapping, rotors_simulator, mav_comm, eigen_catkin, eigen_checks, etc...

2-1. NBVP

Unfold to see
  • Install dependencies and get the code
    cd ~/catkin_ws/src
    git clone https://github.com/ethz-asl/nbvplanner.git
    cd nbvplanner
    git submodule update --init --recursive
    
    rm -r rotors # install it as above Section 1-2.
    cd mav_comm && git pull origin master
  • Change CMakeLists.txt and build the code
    cd ~/catkin_ws/src/nbvplanner/nbvplanner
    wget -O CMakeLists.txt https://raw.githubusercontent.com/engcang/exploration-algorithms/main/nbvp/nbvplanner/CMakeLists.txt
    cd ~/catkin_ws/src/nbvplanner/interface_nbvp_rotors
    wget -O CMakeLists.txt https://raw.githubusercontent.com/engcang/exploration-algorithms/main/nbvp/interface_nbvp_rotors/CMakeLists.txt
    
    cd ~/catkin_ws
    catkin build -DCMAKE_BUILD_TYPE=Release

2-2. GBP2

Unfold to see
  • Install dependencies and get the code
    sudo apt install python-catkin-tools \
    libgoogle-glog-dev \
    ros-melodic-joy \
    ros-melodic-twist-mux \
    ros-melodic-interactive-marker-twist-server \
    ros-melodic-octomap-ros
    
    cd catkin_ws
    git clone https://github.com/ntnu-arl/gbplanner_ros.git -b gbplanner2
    
    wstool init
    wstool merge ./gbplanner_ros/packages_ssh.rosinstall
    wstool update
    
    rm -r src/sim/rotors_simulator #install it as above Section 1-2.
  • Build
    cd ~/catkin_ws
    catkin build -DCMAKE_BUILD_TYPE=Release

2-3. GBP1

Unfold to see
  • Clone and build the code
    cd ~/catkin_ws
    git clone https://github.com/ntnu-arl/gbplanner_ws.git
    cd gbplanner_ws
    git checkout origin/melodic
    wstool init
    wstool merge packages_https.rosinstall
    wstool update
    
    mv gbplanner_ws/src/* ~/catkin_ws/src/
    cd ~/catkin_ws
    rm -r src/sim/rotors_simulator # install it as above Section 1-2.  
  • Change the path of Eigen in
    • gbplanner_ros/gbplanner/include/gbplanner/params.h
    • gbplanner_ros/gbplanner/include/gbplanner/gbplanner_rviz.h
    • gbplanner_ros/gbplanner/include/gbplanner/geofence_manager.h
    • gbplanner_ros/gbplanner/include/gbplanner/graph_manager.h
    • gbplanner_ros/gbplanner/include/gbplanner/map_manager.h
    • gbplanner_ros/gbplanner/include/gbplanner/rrg.h
      //#include <eigen3/Eigen/Dense>
      #include <Eigen/Dense>
  • Build
    cd ~/catkin_ws
    catkin build -DCMAKE_BUILD_TYPE=Release
    
    !Optionally, for use with OctoMap
    catkin build -DCMAKE_BUILD_TYPE=Release -DUSE_OCTOMAP=1

2-4. MBP

Unfold to see
  • Get the code and build
    git clone https://github.com/ntnu-arl/mbplanner_ws.git
    cd mbplanner_ws
    git checkout melodic-devel
    wstool init
    wstool merge packages_https.rosinstall
    wstool update
    
    mv mbplanner_ws/src/* ~/catkin_ws/src/
    cd ~/catkin_ws
    rm -r src/sim/rotors_simulator # install it as above Section 1-2.
  • Fix the code error
    • exploration/mbplanner/mbplanner_ros/planner_common/src/params.cpp
    • Line 847 (in MBParams::loadParams(std::string ns))
      // Add
      return true;
  • Change the path of Eigen in exploration/mbplanner_ros/planner_common/include/planner_common/visualizer.h
    //#include <eigen3/Eigen/Dense>
    #include <Eigen/Dense>
  • Build
    cd ~/catkin_ws
    catkin build -DCMAKE_BUILD_TYPE=Release
    
    !Optionally, for use with OctoMap
    catkin build -DCMAKE_BUILD_TYPE=Release -DUSE_OCTOMAP=1
  • Trouble shooting for planner_common
    • When opencv path errors from image_proc,
      • Change the directory of opencv in /opt/ros/melodic/share/image_proc/cmake/image_procConfig.cmake

2-5. AEP

Unfold to see
  • Install dependencies and build the code
    sudo apt install ros-melodic-octomap* 
    sudo apt-get install libspatialindex-dev
    python2 -m pip install rtree
    
    cd ~/catkin_ws/src/
    git clone https://github.com/catkin/catkin_simple.git
    git clone https://github.com/mseln/aeplanner.git
    cd ..
    catkin build -DCMAKE_BUILD_TYPE=Release
    
    ## If PCL errors in rpl_exploration,
    ## change compiler to newer than c++14
    ## in line 4 for CMakeLists.txt of rpl_exploration

2-6. FUEL

Unfold to see
  • Install dependencies
    sudo apt-get install libarmadillo-dev
    sudo apt-get install libdw-dev
    git clone https://github.com/stevengj/nlopt.git
    cd nlopt
    mkdir build && cd build
    cmake ..
    make
    sudo make install
  • Get the code and change CMakeLists.txt of bsline_opt
    cd ~/catkin_ws/src
    git clone https://github.com/HKUST-Aerial-Robotics/FUEL.git
    cd FUEL/fuel_planner/bspline_opt
    wget -O CMakeLists.txt https://raw.githubusercontent.com/engcang/exploration-algorithms/main/fuel/CMakeLists.txt
  • Change compiler into c++14 in all CMakeLists.txt files
    #set(CMAKE_CXX_FLAGS "-std=c++11")
    set(CMAKE_CXX_FLAGS "-std=c++14")
  • Fix the code error
    • FUEL/fuel_planner/path_searching/src/kinodynamic_astar.cpp
    • Line 654 (in int KinodynamicAstar::timeToIndex(double time))
      // Add
      return idx;
  • Build the code
    cd ~/catkin_ws
    catkin build -DCMAKE_BUILD_TYPE=Release

2-7. DSVP

Unfold to see
  • Install dependencies and get the code
    sudo apt install ros-melodic-octomap-ros libgoogle-glog-dev libgflags-dev
    
    cd ~/catkin_ws/src
    git clone https://github.com/HongbiaoZ/dsv_planner.git
    cd dsv_planner
    git checkout origin/melodic
  • Fix CMakeLists.txt in dsv_planner/src/volumetric_mapping/octomap_world
    #target_link_libraries(octomap_manager ${PROJECT_NAME} glog)
    target_link_libraries(octomap_manager ${PROJECT_NAME} glog gflags)
  • Fix CMakeLists.txt in dsv_planner/src/dsvplanner/dsvplanner
    find_package(catkin REQUIRED COMPONENTS
      roscpp
      geometry_msgs
      visualization_msgs
      message_generation
      octomap_world
      tf
      kdtree
      std_msgs
      nav_msgs
      misc_utils
      graph_planner #ADDED
      graph_utils
    )
  • Change the path of Eigen in
    • dsv_planner/src/dsvplanner/dsvplanner/include/dsvplanner/drrt_base.h
    • dsv_planner/src/dsvplanner/dsvplanner/src/drrtp.cpp
    • dsv_planner/src/dsvplanner/dsvplanner/src/drrtp_node.cpp
      //#include <eigen3/Eigen/Dense>
      #include <Eigen/Dense>
  • Build the code
    cd ~/catkin_ws
    catkin build -DCMAKE_BUILD_TYPE=Release

2-8. TARE

Unfold to see
  • Get and build the code
    cd ~/catkin_ws/src
    git clone https://github.com/caochao39/tare_planner.git
    cd ..
    
    sudo apt remove libflags* ### as it is using OR-Tools
    
    catkin build -DCMAKE_BUILD_TYPE=Release

2-9. OIPP - without Unreal, Gazebo instead (thanks to Dongkyu Lee)

Unfold to see
  • Get dependencies
    sudo apt-get install python-wstool python-catkin-tools
    sudo apt-get install ros-melodic-cmake-modules ros-melodic-control-toolbox ros-melodic-joy ros-melodic-octomap-ros ros-melodic-mavlink ros-melodic-geographic-msgs autoconf libyaml-cpp-dev protobuf-compiler libgoogle-glog-dev liblapacke-dev libgeographic-dev
    
    cd ~/catkin_ws/src
    git clone https://github.com/ethz-asl/mav_active_3d_planning
    wstool init
    wstool merge mav_active_3d_planning/mav_active_3d_planning_https.rosinstall
    wstool update
    
    rm -r rotors_simulator # install it as above Section 1-2.
    rm -r yaml_cpp_catkin # prevent confliction
    
    cd ..
    catkin build -DCMAKE_BUILD_TYPE=Release

2-10. ERRT

Unfold to see
  • Install dependencies

    sudo apt-get update
    sudo apt-get --with-new-pkgs upgrade -y
    sudo apt-get install -y mesa-utils \
                            libgl1-mesa-glx \
                            vim \
                            tmuxinator \
                            python3-catkin-tools \
                            python3-osrf-pycommon \
                            python3-pip \
                            libtbb-dev \
                            ros-noetic-octomap-server \
                            ros-noetic-octomap-ros \
                            ros-noetic-octomap-rviz-plugins \
                            ros-noetic-octomap-mapping \
                            libtool \
                            libgoogle-glog-dev \
                            libnlopt-dev \
                            libsuitesparse-dev \
                            ros-noetic-nlopt \
                            liblapacke-dev \
                            ros-noetic-gtsam \
                            ros-noetic-rosmon \
                            iputils-ping \
                            apt-transport-https ca-certificates \
                            openssh-server python3-pip exuberant-ctags \
                            git vim tmux nano htop sudo curl wget gnupg2 \
                            bash-completion \
                            libcanberra-gtk3-0 \
                            ros-noetic-gmapping ros-noetic-slam-gmapping ros-noetic-openslam-gmapping \
                            ros-noetic-joy \
                            ros-noetic-twist-mux \
                            ros-noetic-interactive-marker-twist-server \
                            ros-noetic-fath-pivot-mount-description \
                            ros-noetic-flir-camera-description \
                            ros-noetic-realsense2-description \
                            ros-noetic-lms1xx \
                            ros-noetic-robot-localization \
                            ros-noetic-teleop-twist-keyboard \
                            ros-noetic-teleop-twist-joy \
                            ros-noetic-rviz-imu-plugin \
                            ros-noetic-gmapping \
                            ros-noetic-mavros-msgs \
                            ros-noetic-move-base-msgs \
                            ros-noetic-tf2-sensor-msgs \
                            python3-catkin-tools \
                            python3-osrf-pycommon \
                            libtbb-dev \
                            qtbase5-dev \
                            qtdeclarative5-dev \
                            libqt5x11extras5-dev
    pip3 install opengen
    pip3 install gdown
    
    curl https://sh.rustup.rs -sSf | sh -s -- -y
    # Add Rust binaries to the PATH
    RUN echo "source $HOME/.cargo/env" >> /home/$USER_NAME/.bashrc
  • Install ROS dependencies

    git clone https://github.com/ethz-asl/eigen_checks.git
    git clone https://github.com/catkin/catkin_simple.git
    git clone https://github.com/ethz-asl/eigen_catkin.git
    git clone https://github.com/ntnu-arl/lidar_simulator.git
    git clone https://github.com/ethz-asl/mav_comm.git
    git clone https://github.com/ros-planning/navigation_msgs.git
    git clone https://github.com/ethz-asl/numpy_eigen.git
    git clone --branch melodic-devel https://github.com/ros-perception/perception_pcl.git
    git clone https://github.com/ros/xacro.git
    git clone https://github.com/ethz-asl/catkin_boost_python_buildtool.git
    git clone https://github.com/LTU-RAI/darpa_subt_worlds.git
    git clone https://github.com/LTU-RAI/ufomap.git
    git clone https://github.com/LTU-RAI/geometry2.git
    git clone https://github.com/aakapatel/mav_control_rw.git

    [Recommended] If you want to use LTU-RAI lab version of rotors_simulator, install as follows:

    git clone https://github.com/LTU-RAI/rotors_simulator.git && cd rotors_simulator && git pull
  • Add compiler option c++17 in rotors_gazebo_plugins

    add_compile_options(-std=c++17)
  • Get the source code and build (NOTE: modify cargo build target path correctly)

    git clone https://github.com/LTU-RAI/ExplorationRRT.git
    /bin/bash -c 'source $HOME/.cargo/env; cd /home/$USERNAME/catkin_ws/src/ExplorationRRT; python3 rrt_costgen.py'
    catkin build errt
  • Download gazebo models provied in errt (if you want)

    cd ExplorationRRT/docker
    gdown --id 1TDbXF9He_LXYY57Xo3tOxvEVYH3kPtS8
    gdown --id 1y7BDt0tjK9Ml7MlTxUwOTG8ZygO_dpI0
    unzip models.zip 
    unzip ignition_models.zip 

    In your .bashrc or .zshrc, add downloaded models directory in GAZEBO_MODEL_PATH

    export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:~/<your_ws>/src/ExplorationRRT/docker/ignition_models:~/<your_ws>/src/ExplorationRRT/docker/models

Run Demos

1. NBVP

Unfold to see
  • Important: Put <plugin name="ros_interface_plugin" filename="librotors_gazebo_ros_interface_plugin.so"/> into Gazebo .world file
  • Run the demo
    roslaunch interface_nbvp_rotors flat_exploration.launch

2. GBP2 - it does not work for me yet

Unfold to see
  • Run the demo
    roslaunch gbplanner rmf_sim.launch
    or
    roslaunch gbplanner smb_sim.launch

3. GBP1

Unfold to see
  • Check map_config_file, if it is octomap or voxblox
    <arg name="map_config_file" default="$(arg octomap_config_file)"/>
    <arg name="map_config_file" default="$(arg voxblox_config_file)"/>
  • Run the demo
    roslaunch gbplanner gbplanner_sim.launch
    rosservice call /planner_control_interface/std_srvs/automatic_planning "{}" 

4. MBP

Unfold to see
  • Check map_config_file, if it is octomap or voxblox
    <arg name="map_config_file" default="$(arg octomap_config_file)"/>
    <arg name="map_config_file" default="$(arg voxblox_config_file)"/>
  • Run the demo
    roslaunch mbplanner mbplanner_m100_sim.launch
    rosservice call /planner_control_interface/std_srvs/automatic_planning "{}" 

5. AEP (no official demo provided, I added environments)

Unfold to see
  • Get config files and Gazebo models and build
    git clone https://github.com/engcang/exploration-algorithms --recursive
    mv exploration-algorithms/aep/ouster_gazebo_plugins ~/catkin_ws/src/
    mv exploration-algorithms/aep/gazebo_env ~/catkin_ws/src/
    mv exploration-algorithms/aep/rpl_exploraiton ~/catkin_ws/src/aeplanner/
    
    cd ~/catkin_ws
    catkin build -DCMAKE_BUILD_TYPE=Release
  • Set Gazebo paths
    cd ~/catkin_ws/src/gazebo_env/gazebo_maps/reconstruction
    tar -xf recon3.tar.xz
    
    gedit ~/.bashrc
    
    !Then, edit GAZEBO_PLUGIN_PATH and GAZEBO_MODEL_PATH!
    
    export GAZEBO_PLUGIN_PATH=:/home/$(whoami)/PX4-Autopilot/build/px4_sitl_default/build_gazebo:$GAZEBO_PLUGIN_PATH
    export GAZEBO_MODEL_PATH=/home/$(whoami)/catkin_ws/src/gazebo_env/drone_models:/home/$(whoami)/catkin_ws/src/gazebo_env/gazebo_maps/reconstruction:/home/$(whoami)/PX4-Autopilot/Tools/sitl_gazebo/models:$GAZEBO_MODEL_PATH
  • Run the demo
    roslaunch rpl_exploration px4_sitl_gazebo.launch
    # choose sensor
    roslaunch rpl_exploration rpl_exploration.launch sensor:=lidar
    roslaunch rpl_exploration rpl_exploration.launch sensor:=rgbd
    # arming & offboarding
    rosservice call /mavros/cmd/arming "value: true"
    rosservice call /mavros/set_mode "base_mode: 0 custom_mode: 'OFFBOARD'"

6. FUEL

Unfold to see
  • Run the demo
    roslaunch exploration_manager rviz.launch
    roslaunch exploration_manager exploration.launch
  • Start with 2D Nav Goal in Rviz

7. DSVP

Unfold to see
  • Run the demo
    roslaunch vehicle_simulator system_garage.launch
    roslaunch dsvp_launch explore_garage.launch

8. TARE

Unfold to see
  • Run the demo
    roslaunch vehicle_simulator system_garage.launch
    roslaunch tare_planner explore_garage.launch
  • Trouble shooting
    • When symbol lookup error: tare_planner/or-tools/lib/libortools.so: undefined symbol: _ZN6gflags14FlagRegistererC1IiEEPKcS3_S3_PT_S5_
      • Check if libortools.so is referring the right libraries
      • If reffering wrong, delete or rename the wrong libraries temporarily
        ldd tare_planner/or-tools/lib/ldd libortool.so
        
        ! wrong output
        libgflags.so.2.2 => sota_ws/devel/lib/libgflags.so.2.2 (0x00007f036830d000)
        libglog.so.0 => sota_ws/devel/lib/libglog.so.0 (0x00007f03680dc000)
        
        ! after delete/rename wrong files
        sudo ldconfig
        ldd tare_planner/or-tools/lib/ldd libortool.so        
        
        ! correct output
        libgflags.so.2.2 => tare_planner/src/tare_planner/or-tools/lib/./libgflags.so.2.2 (0x00007fe6749e0000)
        libglog.so.0 => tare_planner/src/tare_planner/or-tools/lib/./libglog.so.0 (0x00007fe6747a3000)

9. OIPP without Unreal, Gazebo instead (thanks to Dongkyu Lee)

Unfold to see
  • Get modified files for running without Unreal but Gazebo instead
    git clone https://github.com/engcang/exploration-algorithms --recursive
    cd exploration-algorithms/oipp
    mv active_3d_planning_app_reconstruction ~/catkin_ws/src/mav_active_3d_planning/
    mv active_3d_planning_core ~/catkin_ws/src/mav_active_3d_planning/
    
    cd ~/catkin_ws
    catkin build -DCMAKE_BUILD_TYPE=Release
  • Run demo
    roslaunch active_3d_planning_app_reconstruction no_unreal_run_experiment.launch
    rosservice call /planner/planner_node/toggle_running "data: true"

10. ERRT

Unfold to see
  • Run demo
    roslaunch errt server.launch
    roslaunch errt errt.launch
    roslaunch rotors_gazebo errt_mav.launch
    roslaunch mav_linear_mpc mav_linear_mpc_sim.launch mav_name:=hummingbird
    rosservice call /hummingbird/takeoff "{}"
    Note: errt_mav.launch only works for LTU-RAI version of rotors_gazebo. Set up your own rotors launch for your custom world file.

About

[Docker provided] How to build, install and run open-source exploration algorithms

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Languages

  • C++ 74.9%
  • Python 20.2%
  • CMake 4.6%
  • Shell 0.3%