Hello
I am currently working on getting RTAB-Map workin on a Robot with an industrial PC where Linux is running on. There I want to get 3D Mapping done with a Realsense D435 Camera + Lasersensor. The Odometry from the Robot Itself (Taurob Tracker) doesnt work all too fine so I am trying to get Odometry running with Hector Slam. I tried several of the Demo Codes and adjusted them so they run with the Topics of the Cameras; Lasersensors and hector mapping. Still it seems I dont get anything to run. Mostly because either the RTAB-Map gives error messages that it doesnt get Data from Topics or RTAB-Map itself fails to start. I checked all the Inputs I give to RTAB-Map to create a 3d Pointcloud in RVIZ and each Topic by itself does run and gives out messages, but as soon as I take them for the mapping i just dont get anything to work. Error messages look like this: Here is the Code i am using where I try to only get the front camera working at the moment <launch> <arg name="stereo" default="false"/> <arg name="rtabmapviz" default="false" /> <arg name="rviz" default="false" /> <arg name="localization" default="false"/> <arg name="use_sim_time" default="false"/> cd <arg name="cfg" default="" /> <arg name="gui_cfg" default="~/.ros/rtabmap_gui.ini" /> <arg name="rviz_cfg" default="$(find rtabmap_ros)/launch/config/rgbd.rviz" /> <arg name="frame_id" default="base_link"/> <arg name="odom_frame_id" default=""/> <arg name="map_frame_id" default="map"/> <arg name="ground_truth_frame_id" default=""/> <arg name="ground_truth_base_frame_id" default=""/> <arg name="namespace" default="rtabmap"/> <arg name="database_path" default="~/.ros/rtabmap.db"/> <arg name="queue_size" default="10"/> <arg name="wait_for_transform" default="0.5"/> <arg name="args" default="delete_db_on_start"/> <arg name="rtabmap_args" default="$(arg args)"/> <arg name="launch_prefix" default=""/> <arg name="output" default="screen"/> <arg if="$(arg stereo)" name="approx_sync" default="false"/> <arg unless="$(arg stereo)" name="approx_sync" default="true"/> <arg name="rgb_topic" default="/rs_front/color/image_raw" /> <arg name="depth_topic" default="/rs_front/depth/image_rect_raw" /> <arg name="camera_info_topic" default="/rs_front/color/camera_info" /> <arg name="depth_camera_info_topic" default="/rs_front/depth/camera_info" /> <arg name="stereo_namespace" default="/camera"/> <arg name="left_image_topic" default="$(arg stereo_namespace)/infra1/image_rect_raw" /> <arg name="right_image_topic" default="$(arg stereo_namespace)/infra2/image_rect_raw" /> <arg name="left_camera_info_topic" default="$(arg stereo_namespace)/infra1/camera_info" /> <arg name="right_camera_info_topic" default="$(arg stereo_namespace)/infra2/camera_info" /> <arg name="rgbd_sync" default="true"/> <arg name="approx_rgbd_sync" default="true"/> <arg name="subscribe_rgbd" default="$(arg rgbd_sync)"/> <arg name="rgbd_topic" default="rgbd_image" /> <arg name="depth_scale" default="1.0" /> <arg name="compressed" default="false"/> <arg name="rgb_image_transport" default="compressed"/> <arg name="depth_image_transport" default="compressedDepth"/> <arg name="subscribe_scan" default="true"/> <arg name="scan_topic" default="/scan_multi"/> <arg name="subscribe_scan_cloud" default="false"/> <arg name="scan_cloud_topic" default="/scan_cloud"/> <arg name="scan_normal_k" default="0"/> <arg name="visual_odometry" default="false"/> <arg name="icp_odometry" default="false"/> <arg name="odom_topic" default="/scanmatch_odom"/> <arg name="vo_frame_id" default="$(arg odom_topic)"/> <arg name="odom_tf_angular_variance" default="1"/> <arg name="odom_tf_linear_variance" default="1"/> <arg name="odom_args" default=""/> <arg name="odom_sensor_sync" default="false"/> <arg name="odom_guess_frame_id" default=""/> <arg name="odom_guess_min_translation" default="0"/> <arg name="odom_guess_min_rotation" default="0"/> <arg name="subscribe_user_data" default="false"/> <arg name="user_data_topic" default="/user_data"/> <arg name="user_data_async_topic" default="/user_data_async" /> <arg if="$(arg compressed)" name="rgb_topic_relay" default="$(arg rgb_topic)_relay"/> <arg unless="$(arg compressed)" name="rgb_topic_relay" default="$(arg rgb_topic)"/> <arg if="$(arg compressed)" name="depth_topic_relay" default="$(arg depth_topic)_relay"/> <arg unless="$(arg compressed)" name="depth_topic_relay" default="$(arg depth_topic)"/> <arg if="$(arg compressed)" name="left_image_topic_relay" default="$(arg left_image_topic)_relay"/> <arg unless="$(arg compressed)" name="left_image_topic_relay" default="$(arg left_image_topic)"/> <arg if="$(arg compressed)" name="right_image_topic_relay" default="$(arg right_image_topic)_relay"/> <arg unless="$(arg compressed)" name="right_image_topic_relay" default="$(arg right_image_topic)"/> <group ns="$(arg namespace)"> <group unless="$(arg stereo)"> <node if="$(arg compressed)" name="republish_rgb" type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg rgb_topic) raw out:=$(arg rgb_topic_relay)" /> <node if="$(arg compressed)" name="republish_depth" type="republish" pkg="image_transport" args="$(arg depth_image_transport) in:=$(arg depth_topic) raw out:=$(arg depth_topic_relay)" /> <node if="$(arg rgbd_sync)" pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="$(arg output)"> <remap from="rgb/image" to="$(arg rgb_topic_relay)"/> <remap from="depth/image" to="$(arg depth_topic_relay)"/> <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/> <remap from="rgbd_image" to="$(arg rgbd_topic)"/> </node> </group> <group if="$(arg stereo)"> <node if="$(arg compressed)" name="republish_left" type="republish" pkg="image_transport" args="compressed in:=$(arg left_image_topic) raw out:=$(arg left_image_topic_relay)" /> <node if="$(arg compressed)" name="republish_right" type="republish" pkg="image_transport" args="compressed in:=$(arg right_image_topic) raw out:=$(arg right_image_topic_relay)" /> <node if="$(arg rgbd_sync)" pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/stereo_sync" output="$(arg output)"> <remap from="left/image_rect" to="$(arg left_image_topic)"/> <remap from="right/image_rect" to="$(arg right_image_topic)"/> <remap from="left/camera_info" to="$(arg left_camera_info_topic)"/> <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/> <remap from="rgbd_image" to="$(arg rgbd_topic)"/> </node> </group> <group unless="$(arg icp_odometry)"> <group if="$(arg visual_odometry)"> <node unless="$(arg stereo)" pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="$(arg output)" args="$(arg rtabmap_args) $(arg odom_args)" launch-prefix="$(arg launch_prefix)"> <remap from="rgb/image" to="$(arg rgb_topic_relay)"/> <remap from="depth/image" to="$(arg depth_topic_relay)"/> <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/> <remap from="rgbd_image" to="$(arg rgbd_topic)"/> <remap from="odom" to="$(arg odom_topic)"/> </node> <node if="$(arg stereo)" pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="$(arg output)" args="$(arg rtabmap_args) $(arg odom_args)" launch-prefix="$(arg launch_prefix)"> <remap from="left/image_rect" to="$(arg left_image_topic_relay)"/> <remap from="right/image_rect" to="$(arg right_image_topic_relay)"/> <remap from="left/camera_info" to="$(arg left_camera_info_topic)"/> <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/> <remap from="rgbd_image" to="$(arg rgbd_topic)"/> <remap from="odom" to="$(arg odom_topic)"/> </node> </group> </group> <node if="$(arg icp_odometry)" pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="$(arg output)" args="$(arg rtabmap_args) $(arg odom_args)" launch-prefix="$(arg launch_prefix)"> <remap from="scan" to="$(arg scan_topic)"/> <remap from="scan_cloud" to="$(arg scan_cloud_topic)"/> <remap from="odom" to="$(arg odom_topic)"/> </node> <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="$(arg output)" args="$(arg rtabmap_args)" launch-prefix="$(arg launch_prefix)"> <remap from="rgb/image" to="$(arg rgb_topic_relay)"/> <remap from="depth/image" to="$(arg depth_topic_relay)"/> <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/> <remap from="rgbd_image" to="$(arg rgbd_topic)"/> <remap from="left/image_rect" to="$(arg left_image_topic_relay)"/> <remap from="right/image_rect" to="$(arg right_image_topic_relay)"/> <remap from="left/camera_info" to="$(arg left_camera_info_topic)"/> <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/> <remap from="scan" to="$(arg scan_topic)"/> <remap from="scan_cloud" to="$(arg scan_cloud_topic)"/> <remap from="user_data" to="$(arg user_data_topic)"/> <remap from="user_data_async" to="$(arg user_data_async_topic)"/> <remap from="odom" to="$(arg odom_topic)"/> </node> <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(arg gui_cfg)" output="$(arg output)" launch-prefix="$(arg launch_prefix)"> <remap from="rgb/image" to="$(arg rgb_topic_relay)"/> <remap from="depth/image" to="$(arg depth_topic_relay)"/> <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/> <remap from="rgbd_image" to="$(arg rgbd_topic)"/> <remap from="left/image_rect" to="$(arg left_image_topic_relay)"/> <remap from="right/image_rect" to="$(arg right_image_topic_relay)"/> <remap from="left/camera_info" to="$(arg left_camera_info_topic)"/> <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/> <remap from="scan" to="$(arg scan_topic)"/> <remap from="scan_cloud" to="$(arg scan_cloud_topic)"/> <remap from="odom" to="$(arg odom_topic)"/> </node> </group> <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(arg rviz_cfg)"/> <node if="$(arg rviz)" pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb"> <remap from="left/image" to="$(arg left_image_topic_relay)"/> <remap from="right/image" to="$(arg right_image_topic_relay)"/> <remap from="left/camera_info" to="$(arg left_camera_info_topic)"/> <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/> <remap from="rgb/image" to="$(arg rgb_topic_relay)"/> <remap from="depth/image" to="$(arg depth_topic_relay)"/> <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/> <remap from="cloud" to="voxel_cloud" /> </node> </launch> Here are Picture of the TF tree and also the Topics that are Broadcasted: |
Administrator
|
Hi,
rtabmap is crashing at start. It can be related to wrong libraries used at runtime (2 versions of same library installed) or an Eigen problem (-march=native flag). Did you build rtabmap from source? If so, can you show cmake output of the rtabmap library? cheers, Mathieu |
This post was updated on .
First, thanks a lot for the very fast answer I didnt think it would be as fast and unfortunately didnt get an email.
The problem is, it doesnt always crash. I had it perfectly working with visual odometry. ALso i built be libraries from source and also use rtabmap_ros. Only if I try to get odometry from hector mapping like it is stated in the tutorial on how to set up rtabmap on your robot --> source http://wiki.ros.org/rtabmap_ros/Tutorials/SetupOnYourRobot When i start using the odometry topic provided by hector mapping rtabmap is crashing. it also sometimes craches with my base_link of the robot then i have to switch to chassis_link. So what I really cant figure out is how to get my realsense d435 cameras working together with my Lasers to provide good odometry for mapping with the robot. Here is a Link to the robot: Taurob Tracker As stated before we installed an external industrial PC on the chassis for processing. Edit: Here is the output from cmake twmr@twmr-desktop:~/rtabmap/build$ cmake .. -- The imported target "vtkRenderingPythonTkWidgets" references the file "/usr/lib/x86_64-linux-gnu/libvtkRenderingPythonTkWidgets.so" but this file does not exist. Possible reasons include: * The file was deleted, renamed, or moved to another location. * An install or uninstall procedure did not complete successfully. * The installation package was faulty and contained "/usr/lib/cmake/vtk-6.2/VTKTargets.cmake" but not all the files it references. -- The imported target "vtk" references the file "/usr/bin/vtk" but this file does not exist. Possible reasons include: * The file was deleted, renamed, or moved to another location. * An install or uninstall procedure did not complete successfully. * The installation package was faulty and contained "/usr/lib/cmake/vtk-6.2/VTKTargets.cmake" but not all the files it references. -- PCL definitions don't contain "-march=native", make sure all libraries using Eigen are also compiled without that flag to avoid some segmentation faults (with gdb referring to some Eigen functions). -- Found OpenMP -- Found OpenCV: /opt/ros/kinetic/include/opencv-3.3.1-dev;/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv -- Found PCL: /usr/include/pcl-1.7;/usr/include/eigen3;/usr/include;/usr/include/ni;/usr/include/openni2;/usr/include/vtk-6.2;/usr/include/hdf5/openmpi;/usr/lib/openmpi/include/openmpi/opal/mca/event/libevent2021/libevent;/usr/lib/openmpi/include/openmpi/opal/mca/event/libevent2021/libevent/include;/usr/lib/openmpi/include;/usr/lib/openmpi/include/openmpi;/usr/include/freetype2;/usr/include/x86_64-linux-gnu/freetype2;/usr/include/x86_64-linux-gnu;/usr/include/jsoncpp;/usr/include/tcl;/usr/include/libxml2;/usr/include/python2.7 -- Found ZLIB: /usr/include -- Found Freenect: /usr/include -- Found OpenNI2: /usr/include/openni2 -- Old g2o version detected with c++03 interface (config file: /opt/ros/kinetic/include/g2o/config.h). -- Found g2o: /opt/ros/kinetic/include;/usr/include/suitesparse;/usr/include/suitesparse -- Found RealSense2: -- Found octomap 1.8.1: /opt/ros/kinetic/include -- Found Pthreads -- -------------------------------------------- -- Info : -- Version : 0.17.3 -- CMAKE_INSTALL_PREFIX = /home/twmr/catkin_ws/devel -- CMAKE_BUILD_TYPE = Release -- CMAKE_INSTALL_LIBDIR = lib -- BUILD_APP = ON -- BUILD_TOOLS = ON -- BUILD_EXAMPLES = ON -- BUILD_SHARED_LIBS = ON -- CMAKE_CXX_FLAGS = -fmessage-length=0 -fopenmp -std=c++11 -- PCL_DEFINITIONS = -DEIGEN_USE_NEW_STDVECTOR;-DEIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET;-DFLANN_STATIC;-Dqh_QHpointer -- With OpenCV 3 xfeatures2d module (SIFT/SURF/BRIEF/FREAK) = YES (License: Non commercial) -- With Freenect = YES (License: Apache v2 and/or GPLv2) -- With OpenNI2 = YES (License: Apache v2) -- With Freenect2 = NO (libfreenect2 not found) -- With Kinect for Windows 2 = NO (Kinect for Windows 2 SDK not found) -- With dc1394 = NO (dc1394 not found) -- With FlyCapture2/Triclops = NO (Point Grey SDK not found) -- With TORO = YES (License: Creative Commons [Attribution-NonCommercial-ShareAlike]) -- With g2o = YES (License: BSD) -- With GTSAM = NO (GTSAM not found) -- With VERTIGO = YES (License: GPLv3) -- With cvsba = NO (cvsba not found) -- With libpointmatcher = NO (libpointmatcher not found) -- With loam_velodyne = NO (loam_velodyne not found) -- With ZED = NO (ZED sdk not found) -- With RealSense = NO (librealsense not found) -- With RealSense2 = YES (License: Apache-2) -- With OCTOMAP = YES (License: BSD) -- With CPUTSDF = NO (CPUTSDF not found) -- With OpenChisel = NO (open_chisel not found) -- With libfovis = NO (libfovis not found) -- With libviso2 = NO (libviso2 not found) -- With dvo_core = NO (dvo_core not found) -- With okvis = NO (okvis not found) -- With ORB_SLAM2 = NO (WITH_G2O should be OFF as ORB_SLAM2 uses its own g2o version) -- With Qt5 = YES (License: Open Source or Commercial) -- -------------------------------------------- -- Configuring done -- Generating done -- Build files have been written to: /home/twmr/rtabmap/build |
Administrator
|
Hi,
Maybe for some reasons the covariance published by hector odometry (/scanmatch_odom) is not good for g2o. Can you output this (assuming odometry topic from hector is called /scanmatch_odom): $ rostopic echo /scanmatch_odom If the crash is happening on loop closure, can you try with TORO optimization? Set Optimizer/Strategy to 0 under rtabmap node: <param name="Optimizer/Strategy" type="string" value="0"/> <param name="Optimizer/Iterations" type="string" value="100"/> Also, looking at the TF tree, normally in this setup it should be rtabmap publishing map -> odom transform. In the referred example, map->odom is disabled for hector: <!-- Tf use --> <param name="pub_map_odom_transform" value="false"/> <param name="pub_map_scanmatch_transform" value="true"/> <param name="pub_odometry" value="true"/> cheers, Mathieu |
Hello matlabbe,
Here is the output of /scanmatch_odom creesy@creesy-TERRA-MOBILE-1547Q ~ $ rostopic echo -n 1 /scanmatch_odom header: seq: 676 stamp: secs: 1531401419 nsecs: 687560661 frame_id: "map" child_frame_id: '' pose: pose: position: x: -0.000984191894531 y: -0.00260353088379 z: 0.0 orientation: x: 0.0 y: 0.0 z: -0.00144329814888 w: 0.999998958445 covariance: [12.971948623657227, 1.4088813066482544, 0.0, 0.0, 0.0, -87.8547592163086, 1.4088813066482544, 14.517890930175781, 0.0, 0.0, 0.0, -655.5228271484375, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -87.8547592163086, -655.5228271484375, 0.0, 0.0, 0.0, 132895.65625] twist: twist: linear: x: 0.0 y: 0.0 z: 0.0 angular: x: 0.0 y: 0.0 z: 0.0 covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] --- Also i have noticed i cant start rtabmap since one of the latest updates anymore at all. The software constantly crashes while launching. Even the normal rtabmap.launch file doesnt work anymore for me. Could there be a problem with shared libraries? because it seems there are seg-faults |
Hello Again
I am currently only trying on my Laptop to regain status quo with rtabmap working. It currently crashes on startup as shown in the Output here:
Thats with the standard Launchfile and only the Topics for the camera changed. The TF tree looks like you mentioned ith odom coming from rtabmap |
Administrator
|
Hi,
There is a FATAL error: [FATAL] (2018-07-12 15:26:39.397) DBDriverSqlite3.cpp:3058::loadLastNodesQuery() Condition (rc == SQLITE_OK) not met! [DB error (0.0.0): misuse of aggregate: MAX()]It looks like the database is corrupted. Can you try starting from a clean database? Remove rtabmap.db in "~/.ros" folder or $ roslaunch rtabmap_ros rtabmap.launch rtabmap_args:="--delete_db_on_start" For the seg faults you are seeing, is rtabmap built from source on the other computer? Which PCL version is used? cheers, Mathieu |
Administrator
|
For the covariance, values seem very high (>>>>0.1). This may cause g2o to fail. Set odom_frame_id arguments to use odometry from TF instead of the topic. You may also try TORO (like explained in my previous post), which is more robust to bad covariances.
|
rtabmap finally doesnt crash anymore, I didnt know a corrupted DB could cause seg_faults. Also I was sure I have set the argument to delete DB on startup to true so thats that. Thank you very much so far and could kiss you currently (too much time spent on trying to resetup rtabmap and everything)
I still need to get an OK mapping going with the odometry from hector slam since the odomery of the robot itself id very awful. The robot has tracks instead of wheels which destroy any normal odometry very fast. also the sensors for odometry arent the best. I will further use this thread if there come any more questions about all this. |
Free forum by Nabble | Edit this page |