Are there docker images with ros support that can run rtabmap with different odometry strategies?
|
Administrator
|
For the standalone benchmark, we have this Dockerfile: https://github.com/introlab/rtabmap/blob/master/docker/jfr2018/Dockerfile
However, as you can see in it, some dependencies are incompatible when included at the same time in rtabmap, so multiple versions of rtabmap had to be created. Making rtabmap_ros supporting all VO at the same time is then not possible unless creating multiple rtabmap_odom packages with different suffixes, which become messy pretty fast. I would recommend to create different rtabmap_ros docker images including a single VO dependency at a time, to do something like: docker run rtabmap_ros_orbslam2 rosrun rtabmap_odom rgbd_odometry --Odom/Strategy=5 ... docker run rtabmap_ros_orbslam3 rosrun rtabmap_odom rgbd_odometry --Odom/Strategy=5 ... docker run rtabmap_ros_msckf_vio rosrun rtabmap_odom rgbd_odometry --Odom/Strategy=8 ... docker run rtabmap_ros_vins_fusion rosrun rtabmap_odom rgbd_odometry --Odom/Strategy=9 ... docker run rtabmap_ros_openvins rosrun rtabmap_odom rgbd_odometry --Odom/Strategy=10 ... You may refer to that dockerfile or this one (latest) to see which version to use and the patches to apply on the dependencies. cheers, Mathieu |
The docker container does not include rtabmap_ros. Do you a have stable container with rtabmap_ros supporting dvo_slam or vins-fusion odometry. The current dockerfile does not cooperate with rtabmap_ros due to old and new versions of rtabmap and rtabmap_ros libraries being built together.
|
Administrator
|
Hi,
The docker images linked above could be fairly straightforward to port to Ubuntu 20.04 and Noetic (just keep the dependencies you need to keep it simple), then build rtabmap_ros at the end. There are some ros examples using different odometry strategies here https://github.com/introlab/rtabmap_ros/blob/master/rtabmap_examples/launch/euroc_datasets.launch Here an example for DVO: FROM introlab3it/rtabmap_ros:noetic RUN apt-get update && apt-get install -y \ git \ wget \ libceres-dev \ ros-${ROS_DISTRO}-sophus \ && rm -rf /var/lib/apt/lists/ # uninstall rtabmap binaries RUN apt-get remove -y ros-${ROS_DISTRO}-rtabmap* # To make "source" working RUN rm /bin/sh && ln -s /bin/bash /bin/sh # Clone dependencies RUN mkdir -p /root/catkin_ws/src WORKDIR /root/catkin_ws/src RUN source /opt/ros/${ROS_DISTRO}/setup.bash && catkin_init_workspace # DVO RUN git clone https://github.com/tum-vision/dvo_slam.git && \ cd dvo_slam && \ git checkout kinetic-devel && \ rm dvo_slam/package.xml && \ rm dvo_benchmark/package.xml && \ rm dvo_ros/package.xml && \ sed -i 's/sophus/Sophus/g' dvo_core/CMakeLists.txt # Catkin_make WORKDIR /root/catkin_ws RUN source /opt/ros/${ROS_DISTRO}/setup.bash && \ catkin_make -DCMAKE_BUILD_TYPE=Release && \ rm -rf build WORKDIR /root # build rtabmap RUN git clone https://github.com/introlab/rtabmap.git RUN source /root/catkin_ws/devel/setup.bash && \ cd rtabmap && \ cd build && \ cmake -DWITH_DVO=ON -DBUILD_EXAMPLES=OFF -DBUILD_TOOLS=OFF .. && \ make -j$(nproc) && \ make install && \ rm -rf * && \ ldconfig # build rtabmap_ros RUN source /root/catkin_ws/devel/setup.bash && \ cd catkin_ws && \ git clone https://github.com/introlab/rtabmap_ros.git src/rtabmap_ros && \ catkin_make -DCMAKE_BUILD_TYPE=Release --only-pkg-with-deps rtabmap_ros && \ rm -rf build RUN echo $'#!/bin/bash\nset -e\nsource "/opt/ros/$ROS_DISTRO/setup.bash" --\nsource "/root/catkin_ws/devel/setup.bash" --\nexec "$@"' > /ros_entrypoint.sh Usage with a D400 realsense camera: # Build image above docker build -t rtabmap:dvo . # Launch camera docker run -it --rm \ --network host \ --privileged \ introlab3it/rtabmap_ros:noetic \ roslaunch realsense2_camera rs_camera.launch align_depth:=true # Launch VSLAM with DVO odometry (with UI), based on example of https://github.com/introlab/rtabmap_ros/tree/master/docker XAUTH=/tmp/.docker.xauth touch $XAUTH xauth nlist $DISPLAY | sed -e 's/^..../ffff/' | xauth -f $XAUTH nmerge - docker run -it --rm \ --privileged \ -e DISPLAY=$DISPLAY \ -e QT_X11_NO_MITSHM=1 \ -e NVIDIA_VISIBLE_DEVICES=all \ -e NVIDIA_DRIVER_CAPABILITIES=all \ -e XAUTHORITY=$XAUTH \ --runtime=nvidia \ --network host \ -v $XAUTH:$XAUTH \ -v /tmp/.X11-unix:/tmp/.X11-unix \ rtabmap:dvo \ roslaunch rtabmap_launch rtabmap.launch \ rtabmap_args:="--delete_db_on_start --Odom/Strategy 4 --Odom/ImageDecimation 2" \ depth_topic:=/camera/aligned_depth_to_color/image_raw \ rgb_topic:=/camera/color/image_raw \ camera_info_topic:=/camera/color/camera_info \ approx_sync:=false # Or launch just DVO odometry without UI: docker run -it --rm --network host \ rtabmap:dvo \ rosrun rtabmap_odom rgbd_odometry \ _Odom/Strategy:=4 \ /rgb/image:=/camera/color/image_raw \ /rgb/camera_info:=/camera/color/camera_info \ /depth/image:=/camera/aligned_depth_to_color/image_raw \ _frame_id:=camera_link \ _Odom/ImageDecimation:=2 On my machine, DVO odom time is < 20 ms per frame with images decimated by 2. cheers, Mathieu |
Free forum by Nabble | Edit this page |