introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
1.01k stars 559 forks source link

How do I convert a recorded database file into a mesh with tsdf setting #235

Closed RajathSwaroop closed 6 years ago

RajathSwaroop commented 6 years ago

Hi, I have been using rtabmap to develop 3-D reconstruction of my room and found it to be great. However I want to visualize it as a mesh and I found that the mesh reconstruction of the map loses resolution. I would like to know if it is possible to use tsdf setting in meshing to improve the mesh file resolution.

When I try selecting tsdf in the list it does not show me the option.

matlabbe commented 6 years ago

For Poisson reconstruction, increase the depth to get more polygons (try 9 or 10). Note however it will be more sensible to noise.

TSDF options are only available if rtabmap is built with cpu-tsdf library or open_chisel.

cheers, Mathieu

RajathSwaroop commented 6 years ago

How do I build the rtabmap with cpu-tsdf? the cmakelist.txt has cpu-tsdf "on". will that be enough or any other flags to be set?

matlabbe commented 6 years ago

You have to download cpu-tsdf, build/install it so that cmake can find it. In the cmake status of rtabmap it will be shown if cputsdf has been found. Example:

-- --------------------------------------------
-- Info :
--   Version : 0.17.0
--   CMAKE_INSTALL_PREFIX = /home/mathieu/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 =  -march=native -msse4.2 -mfpmath=sse ;-DDISABLE_OPENNI2;-DDISABLE_PCAP;-DDISABLE_PNG;-DDISABLE_LIBUSB_1_0
--   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            = YES (License: Apache v2 and/or GPLv2)
--   With Kinect for Windows 2 = NO (Kinect for Windows 2 SDK not found)
--   With dc1394               = YES (License: LGPL)
--   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                = YES (License: BSD)
--   With VERTIGO              = YES (License: GPLv3)
--   With cvsba                = NO (cvsba not found)
--   With libpointmatcher      = YES (License: BSD)
--   With ZED                  = YES (With CUDA)
--   With RealSense            = YES (License: Apache-2)
--   With RealSenseSlam        = YES
--   With OCTOMAP              = YES (License: BSD)
--   With CPUTSDF              = YES (License: BSD)
--   With OpenChisel           = YES (License: ???)
--   With libfovis             = YES (License: GPLv2)
--   With libviso2             = YES (License: GPLv3)
--   With dvo_core             = YES (License: GPLv3)
--   With okvis                = YES (License: BSD)
--   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
RajathSwaroop commented 6 years ago

screenshot from 2018-04-18 16-27-37 I will try that. Also here is a preview of my mapping session. The RTABmap fails to do a loop closure some times and I get a very bad disoriented map.. Can you please tell me if there is a setting to optimize it

matlabbe commented 6 years ago

Which version are you using? Is it with default settings? Is it built with g2o?

You may check with help of the Constraints View in rtabmap-databaseViewer if there is a neighbor link (i.e., odometry link) that has a very gross error. Then look what could have happened, like was there a fast movement of the camera, there were not so many features to track...

If loop closures that should be good are rejected, you could increase RGBD/OptimizeMaxError parameter to accept them.

RajathSwaroop commented 6 years ago

@matlabbe I am using the latest 0.17 version of rtabmap. I have g2o installed and in the CMakelists.txt I have set it to install with g2o. There are enough features to track. I face this issue when I try to record a large room of size 8m x 6m and come back to the same point after recording other parts of the room. I tried changing the threshold setting for similarity threshold and loop closure threshold but nothing changed. I will try to increase the RGBD/OptimizeMaxError

RajathSwaroop commented 6 years ago

@matlabbe I want to perform a sensor fusion for getting accurate Odometry. If I use a kalman filter algorithm on my sensor data that include (visual odometry), IMU data and feed this back under odom topic to the RTABMAP will it perform better. Will RTABmap accept external odometry while computing its own visual odometry at the same time.

RajathSwaroop commented 6 years ago

Also when I record a map and run the rtabmap in localization mode after completion of mapping session, I am able to download the point cloud of the map into the rtabmapviz and see the odometry traces of previous sessions. However, the current /rtabmap/odom gives 0,0 odometry for the reference point where I started localization mode and tends to assume that point as origin instead of finding its co-ordinates from the built map. Can you please let me know if there is any setting to get the current location of camera from the previous map??

matlabbe commented 6 years ago

Yes, rtabmap can use external odometry. Make sure that if rgbd_odometry (or stereo_odometry) is used, it doesn't publish TF (publish_tf=false) to avoid conflicts in the TF tree. See these visual odometry parameters in the sensor fusion example. Then make rtabmap subscribe on your odometry topic (or set odom_frame_id to use TF of your odometry) instead of the one published by visual odometry.

cheers, Mathieu

RajathSwaroop commented 6 years ago

The sensor fusion example takes the IMU data and outputs visual odometry. Instead if I want to provide my own odometry to the rtabmap while also getting its visual odometry is it possible? I want to fuse my odometry and visual odometry so the rtabmap visual odometry does not get lost when the camera encounters featureless space. Is that possible??

Also is there some setting for dynamic obstacle avoidance??

matlabbe commented 6 years ago

Yes it is possible. Just connect your odometry to input odometry of rtabmap. This is what is done in this example, using odometry from the robot instead of visual odometry:

<remap from="odom" to="/base_controller/odom"/>

"dynamic obstacle avoidance" is done by move_base, see this page. If you means how obstacles are added to occupancy grid map generated by rtabmap, see Grid/ parameters:

$ rtabmap --params | grep Grid/
RajathSwaroop commented 6 years ago

Thanks I will check that. I am facing a new issue. Recently I installed rtabmap ros 0.17 version and when I create a map using demo turtlebot mapping launch file I am not able to localize and get the 2-D map of the region. It worked for me with rtabmap 0.16.3 however. The same commands were executed with 0.17 version which done give localization result.

I tried installing 0.16.3 version of rtabmap again but i get this error in ros: error: ‘kGridScan2dMaxFilledRange’ is not a member of ‘rtabmap::Parameters’ parameterMoved(pnh, "grid_unknown_space_filled_max_range", Parameters::kGridScan2dMaxFilledRange(), parameters); ^ rtabmap_ros/CMakeFiles/rtabmap_ros.dir/build.make:510: recipe for target 'rtabmap_ros/CMakeFiles/rtabmap_ros.dir/src/MapsManager.cpp.o' failed

matlabbe commented 6 years ago

If 0.17 libraries are still installed, rtabmap_ros may link to them instead of 0.16.3. Make sure to remove all 0.17 libraries and headers. That parameter is in 0.16.3 Parameters.h.

RajathSwaroop commented 6 years ago

I tried that and It worked. Thanx.

Where do I find the transform code for transform between map and odom. I want to have reference frame as world instead of map and I want to publish transform between world and map myself

matlabbe commented 6 years ago

/map -> /odom is published here. You should not have to modify the code, as you can use simply a static_transform_publisher to publish TF /world -> /map. Then if you would want robot pose in world frame, you would get /world -> /base_link.

cheers, Mathieu

RajathSwaroop commented 6 years ago

Ok that would be an easier workaround. Thanx. Is there any topic published by rtabmap that indicates if the robot has successfully localized in the given map??

matlabbe commented 6 years ago

rtabmap_ros/Info msg:

$ rostopic echo /rtabmap/info/loopClosureId

localized if loopClosureId is not 0.

RajathSwaroop commented 6 years ago

Got it. Thanx

RajathSwaroop commented 6 years ago

When I try localizing the robot in a known map recorded using base footprint and frame id and providing the transform between camera frame and base footprint, the /rtabmap/info/loopClosureId topic sends a 0 after first 5 or 10 seconds of start but I do not get the map in rviz for quite long, sometimes I dont get it forever. Are these two things inter-related? a success in localizing should load the map in rviz or it is a different sequence??

RajathSwaroop commented 6 years ago

Also I recorded a map using robot 1 providing the transform between the robot base footprint and the camera frame, then I use that map to localize robot 2 while providing the correct transform between base footprint of the robot 2 and camera frame and the camera used in both the cases is same intel realsense. Robot 2 is not able to localize even after too many attempts. Is there a reason behind this?

matlabbe commented 6 years ago

If the robots are not identical and the camera is not placed at the same position (angle, height) than on the other robot creating the map, the point of view may cause some challenge for localization. To be more robust to point of view changes, use SURF or SIFT features for the loop closure vocabulary (Kp/DetectorStrategy=0 or 1), and even for visual motion estimation (Vis/FeatureType=0 or 1). Look at the terminal for warnings about if a localization is rejected after valid loop closure detection.

For the previous question, the map 2D occupancy grid map should be republished after the second robot is localized.

cheers, Mathieu

RajathSwaroop commented 6 years ago

Ok I will try those options mentioned above.

What are loop closure threshold and similarity threshold in rtabmap. Changing the value of loop closure improves loop closure in any way?

what is the effect of T_time Max time on the same

RajathSwaroop commented 6 years ago

When I use the rtabmap hand held mapping demo I get this error in the rtabmapviz command terminal: "[ERROR] (2018-05-08 14:02:28.999) MainWindow.cpp:2085::updateMapCloud() map id of node -1 not found!" What does this mean??

The rtabmap does not map anything after this error and just hangs

matlabbe commented 6 years ago

For the error, this is fixed in https://github.com/introlab/rtabmap/commit/5e93803eef1b4643f8a499a571ecb1a36e5738fb Otherwise, just disable Node filtering in Preferences->Node filtering.

For the thresholds, see this paper: Appearance-Based Loop Closure Detection for Online Large-Scale and Long-Term Operation. For similarity threshold (T_similarity), see section III-B. For loop closure threshold (T_loop), see section III-D. For max time (T_time), see section III-F.

For T_loop, setting higher will decrease the chance of bad loop closures (false positives), but will decrease the number of good loop closures as well. In metric SLAM mode, it can be relatively low as loop closures are accepted only if motion estimation can also be computed.

RajathSwaroop commented 6 years ago

Thanks, the node filtering solution seems to work and I could get rid of the error. However I am facing a new issue after that. When I map a region and I move the camera in vertical direction (pitch) the rtabmap constructs multiple surfaces instead of building a nice map. I tried reinstalling the entire rtabmap standalone + ros after completely removing rtabmap from the computer but still have this issue.

Picture here describes the error. screenshot from 2018-05-08 18-21-58

Where can I get the default settings .ini file to get back my settings? I did restore all defaults but that did'nt work for the bad mapping

RajathSwaroop commented 6 years ago

If I wish to give an initial position to the rtabmap before it starts mapping so it maps starting from my given co-ordinates x,y,z and ypr is that possible?? When I run the rtabmap I see initial co-ordinates x,y,z and ypr as 0. Where do I change these?

Also if I am running the camera ros wrapper on a remote machine and want to map using rtabmap on my laptop. I am using the intel realsense camera so I can get the compressed topics of rgb camera and depth data. Can I subscribe to those topics and map with higher frame rate? I looked at the remote mapping example but it uses the data throttle, how do I use JPEG encoded compressed image transport directly

matlabbe commented 6 years ago

For the map errors, it depends on the sensor you are using, some will have more noise than others at different distance.

It is possible to set an initial pose, for odometry node, set "initial_pose" string parameter with format "x y z roll pitch yaw".

You can subscribe to images directly if you have enough bandwidth. See this answer for some comparisons.

cheers, Mathieu

RajathSwaroop commented 6 years ago

I am getting this error when I run the rtabmap launch file on ROS.

[rtabmap/rtabmap-2] process has died [pid 18694, exit code -11, cmd /home/rajath/catkin_ws/devel/lib/rtabmap_ros/rtabmap rgb/image:=/camera/color/image_raw depth/image:=/camera/depth/image_rect_raw rgb/camera_info:=/camera/color/camera_info rgbd_image:=rgbd_image left/image_rect:=/stereo_camera/left/image_rect_color right/image_rect:=/stereo_camera/right/image_rect left/camera_info:=/stereo_camera/left/camera_info right/camera_info:=/stereo_camera/right/camera_info scan:=/scan scan_cloud:=/scan_cloud user_data:=/user_data user_data_async:=/user_data_async odom:=odom name:=rtabmap log:=/home/rajath/.ros/log/4760f7fe-521b-11e8-ac34-b827ebf080fe/rtabmap-rtabmap-2.log]. log file: /home/rajath/.ros/log/4760f7fe-521b-11e8-ac34-b827ebf080fe/rtabmap-rtabmap-2*.log

It does not map anything after this error but just stays in localization mode I guess. I does not recognize anything but I get to see the camera feed in the rtabmapviz

matlabbe commented 6 years ago

rtabmap node has died, you won't get any maps. Try starting the node in gdb to have more info.

RajathSwaroop commented 6 years ago

When I used gdb logging, it does not give me any error. there is no new prompt on the gdb log after some time and the error is'nt being thrown up too. However, it is not mapping anything.

Also I observed that apart from /rtabmap/odom topic other topics do not publish any data but are live. If I try running rqt_tf_tree I see that the map frame is missing. This is what the rqt_tf_tree says frames

matlabbe commented 6 years ago

Yes, gdb won't fix the error, it is just to see more information about the error. You can use "bt" (backtrace) when it crashes to get more logs.

RajathSwaroop commented 6 years ago

Hi I solved that error. Some installation that I did just a while ago had removed the ros image transport and the ros compressed image transport. I had to install those back and the rtabmap is working fine now.

However I get this waning " Costmap2DROS transform timeout. Current time: 1525992706.0815, global_pose stamp: 1525992702.8539, tolerance: 0.5000 [ WARN] [1525992707.081549222]: Costmap2DROS transform timeout. Current time: 1525992707.0815, global_pose stamp: 1525992702.8539, tolerance: 0.5000" is it because of my transform or the rtabmap?

Also I have confirmed that my transform between base_footprint and camera frame does not have any delay. When I run the rtabmap in localization mode I do not get this warning till sometime and the instance I get this warning, I find that the algorithm finds the map.

/rtabmap/rtabmap subscribed to (approx sync): /rtabmap/odom, /camera/color/image_raw/compressed, /camera/depth/image_rect_raw/compressedDepth, /camera/color/camera_info, /rtabmap/odom_info

After rtabmap node starts running I get the msg above after around 45 or 60 seconds and then the warning starts poping up repeatedly. I set compressed:=false rgbd_sync:=true in the arguments when I run the launch file and still I keep getting this. Setting compressed as false is supposed to not use compressed topics?

RajathSwaroop commented 6 years ago

Is there a way of forcing it to not subscribe to the compressed topics of the camera apart from setting compressed false in launch file or the argument?

I even uninstalled and installed Rtabmap standalone and ROS on my machine 2 times removing all the previous lib, rtabmap directories (clean installation). Still the same problem persists

matlabbe commented 6 years ago

By default with rtabmap.launch, compressed is false. It should not subscribe to compressed topics. With "compressed:=false rgbd_sync:=true", you should have something like this:

/rtabmap/rtabmap subscribed to (approx sync):
  /rtabmap/odom
  /rtabmap/rgbd_image,
  /rtabmap/odom_info

Do you restart the roscore between trials? to make sure all rosparam are cleared?

The Costmap2DROS warnings are coming from move_base, you may look at move_base's code to know why.

Can you please list the commands you are using to start all launch files? It will be easier to test them here. Show also "rqt_graph" to better see how nodes are connected.

cheers, Mathieu

RajathSwaroop commented 6 years ago

I got the issue resolved when I restarted the roscore. Probably the rosparams were not cleared. Thanks

RajathSwaroop commented 6 years ago

Is there a way to clear all rosparams without restarting the roscore?

matlabbe commented 6 years ago

See https://answers.ros.org/question/31711/delete-multiple-ros-parameters-at-once/, in particular the clear_params approach.

0dmf0 commented 4 years ago

For Poisson reconstruction, increase the depth to get more polygons (try 9 or 10). Note however it will be more sensible to noise.

TSDF options are only available if rtabmap is built with cpu-tsdf library or open_chisel.

cheers, Mathieu

how to use cpu-tsdf ? Thx

matlabbe commented 4 years ago

If you install cpu-tsdf, cmake would be able to find it. If not installed in default paths, cmake could find CPUTSDFConfig.cmake with:

$ cd rtabmap/build
$ cmake -DCPUTSDF_DIR=/path/to/CPUTSDFConfig.cmake/directory ..

Make sure you see this in cmake status before compiling:

With CPUTSDF              = YES (License: BSD)

For usage, the option will be available in Export dialog.