Hi mathieu
actually, tango is scotch on top of the lidar(as in design02.jpg).Lidar point source is 4 cm backward Tango IR source (assuming Tango IR is the center of Tango device in RTAB, I center it on lidar). Not the best settup but I'm designing 2 3d print stand to mount the phone properly. Main goal of the lidar is to catch what tango don't see. With all my test with tango,I known I'm able to scan a large environment, as long as I have good "unique scene" across the environment to make good loop closure. And results are unbelievable. The only problem is the field of capture. I have to make a lot of back and forth between 2 "unique scene" to scan each angle of the environment. According to you, which design is the best? I made 2 other db. One speed, one slow.$ rosrun tf static_transform_publisher 0 0 0.04 1.57079632679 3.14159265359 0 device Lidar 100 https://wetransfer.com/downloads/419a892f1327737fc9a89f0ebf0cc64f20190228143005/435b51e52dde213191db420754db93fc20190228143005/ef7c88 If I move very slowly, lidar look effectively less off-sync from Tango. High speed increase computation time and error on rotation. Don't know if there is a link. |
Administrator
|
This post was updated on .
Hi,
Can you record and share a small rosbag while doing a full rotation? It will be easier to debug, because it seems to be a synchronization problem. Without rtabmap started: $ rosbag record /tf \ /tango/point_cloud \ /tango/camera/color_1/camera_info \ /tango/camera/color_1/image_raw \ /tango/point_cloud \ /Lidar/points cheers, Mathieu |
Hi,
https://wetransfer.com/downloads/e6a2aa6fe86daccd554a8f336ad4e9f720190312090710/48b3b7437d3d88c0059dbb6a9234464020190312090710/0309d8 sorry for the delay, I was in winter holidays.Hope that can help. Thank you |
Administrator
|
Hi,
the bag seems missing some RGB images and the depth_camera TF is missing from the recorded TF: rosbag info 2019-03-11-17-35-24.bag path: 2019-03-11-17-35-24.bag version: 2.0 duration: 29.0s start: Mar 11 2019 12:35:25.17 (1552322125.17) end: Mar 11 2019 12:35:54.18 (1552322154.18) size: 419.5 MB messages: 5869 compression: none [295/295 chunks] types: sensor_msgs/CameraInfo [c9a58c1b0b154e0e6da7578cb991d214] sensor_msgs/Image [060021388200f6f0f447d0fcd9c64743] sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181] tf2_msgs/TFMessage [94810edda583a504dfda3829e70d7eec] topics: /Lidar/points 293 msgs : sensor_msgs/PointCloud2 /tango/camera/color_1/camera_info 390 msgs : sensor_msgs/CameraInfo /tango/camera/color_1/image_raw 2 msgs : sensor_msgs/Image /tango/point_cloud 53 msgs : sensor_msgs/PointCloud2 /tf 5131 msgs : tf2_msgs/TFMessage Then for TF between device and Lidar, there is something strange as the Lidar frame doesn't look fixed on the device: https://youtu.be/7vyv_XW5cKU Normally the Lidar should be stuck on the device frame, how the device -> Lidar transform is published? |
Hi,
I think I miss something. first, there is 2 times "/tango/camera/color_1/camera_info \" in the rosbag command you ask me to test. Is that nomal? My procces: I launch lidar command first, then I launch this command, and ros tango streamer on the phone: rosrun rtabmap_ros pointcloud_to_depthimage \ cloud:=/tango/point_cloud \ camera_info:=/tango/camera/color_1/camera_info \ _fixed_frame_id:=start_of_service \ _decimation:=8 \ _fill_holes_size:=5 then I execute: rosrun tf static_transform_publisher 0 0 0.04 1.57079632679 3.14159265359 0 device Lidar 100 here is how I publish device -> Lidar transform Like you ask, I don't launch rtab-map, so I assumed I didn't have to execute this previous command: roslaunch rtabmap_ros rtabmap.launch \ rtabmap_args:="--delete_db_on_start --Mem/ImagePreDecimation 2 --Mem/ImagePostDecimation 2" \ visual_odometry:=false \ odom_frame_id:="start_of_service" \ frame_id:="device" \ rgb_topic:=/tango/camera/color_1/image_raw \ depth_topic:=/image \ camera_info_topic:=/tango/camera/color_1/camera_info \ compressed:=true \ depth_image_transport:=raw \ approx_sync:=true \ rgbd_sync:=true \ approx_rgbd_sync:=false \ subscribe_rgbd:=true \ subscribe_scan_cloud:=true \ scan_cloud_topic:=/Lidar/points But I think there is a mistake. I don't define tango phone as "device" since I don't execute this command. So I retry today with this command , so rtab-map launched but on "Pause". Here the result: https://wetransfer.com/downloads/01556f72eba5e8be1ee1a38d91be5ced20190318152415/0bf08101592d6516b2252094a1483f7320190318152415/153f4e By watching several time your video, it's seem to have a delay between device and lidar transform. Lidar follow the same path than device, but with 1 sec delay. where is my mistake? How can we deal with this delay? thank you |
Administrator
|
Hi,
I did an error, the second camera_info was indeed /tango/point_cloud topic instead, I corrected the post above. Your linked bag is missing the images : $ rosbag info 2019-03-18-15-50-45.bag path: 2019-03-18-15-50-45.bag version: 2.0 duration: 28.3s start: Mar 18 2019 10:50:45.59 (1552920645.59) end: Mar 18 2019 10:51:13.89 (1552920673.89) size: 395.3 MB messages: 6476 compression: none [287/287 chunks] types: sensor_msgs/CameraInfo [c9a58c1b0b154e0e6da7578cb991d214] sensor_msgs/Image [060021388200f6f0f447d0fcd9c64743] sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181] tf2_msgs/TFMessage [94810edda583a504dfda3829e70d7eec] topics: /Lidar/points 285 msgs : sensor_msgs/PointCloud2 /tango/camera/color_1/camera_info 102 msgs : sensor_msgs/CameraInfo /tango/camera/color_1/image_raw 1 msg : sensor_msgs/Image /tango/point_cloud 33 msgs : sensor_msgs/PointCloud2 /tf 6055 msgs : tf2_msgs/TFMessage (3 connections) However, I checked with RVIZ the data and the TF between device and Lidar is good (fixed). Here is an example just accumulating the lidar point clouds from that bag: https://youtu.be/OoP1yWY9TJQ The cloud seems good! Example saving all scans in rtabmap: $ roscore $ rosparam set use_sim_time true $ rosrun rtabmap_ros rtabmap -d \ --Rtabmap/DetectionRate 0 \ _odom_frame_id:=start_of_service \ _frame_id:=device \ _subscribe_scan_cloud:=true \ scan_cloud:=assembled_cloud \ _subscribe_depth:=false \ _subscribe_rgb:=false $ rosrun nodelet nodelet standalone rtabmap_ros/point_cloud_assembler \ cloud:=/Lidar/points \ _fixed_frame_id:=start_of_service \ _max_clouds:=10 $ rosbag play --clock 2019-03-18-15-50-45.bag Note that we set Rtabmap/DetectionRate to 0 as we are received the assembled scans at 1 hz. Then exporting the full cloud to PLY (with rtabmap's File->Export Clouds...) and view it in CloudCompare: There are still some small errors in rotation, but I can think you are on a good way. For the synchnorization of Lidar with TF coming from Tango, the best would be to somewhat synchronize the clock between the phone and computer feeding the lidar, though not sure how to do that. For the 1 second lag on the previous post, I think I have seen it with Tango too, where the clock of Tango gets slowly unsynchronized with remote computer after a couple of minutes, the fix is to reboot the phone. cheers, Mathieu |
This post was updated on .
hi mathieu.
I did some other test, tango points and lidar points are better align. The only things I change is the static transform publisher: from : rosrun tf static_transform_publisher 0 0 .04 1.57079632679 3.14159265359 0 device Lidar 100 to: rosrun tf static_transform_publisher 0 0 .04 1.57079632679 3.14159265359 0 device Lidar 5 and the launch command sequence. my tf tree look like this: Things look better but that's not perferct. Don't known if it's an general error or only the precision from tango IMU that shift points of lidar when there are far from source. When I show IMU in rviz, it's seems to shake a lot on rotation. Some other things also disturb me. When I launch "rosrun tf tf_monitor", I got this: RESULTS: for all Frames Frames: Frame: Lidar published by unknown_publisher Average Delay: -0.00470797 Max Delay: 0.00404124 Frame: camera_color published by unknown_publisher(static) Average Delay: 0 Max Delay: 0 Frame: camera_depth published by unknown_publisher(static) Average Delay: 0 Max Delay: 0 Frame: camera_fisheye published by unknown_publisher(static) Average Delay: 0 Max Delay: 0 Frame: device published by unknown_publisher Average Delay: -0.158295 Max Delay: 0 Frame: imu published by unknown_publisher(static) Average Delay: 0 Max Delay: 0 Frame: laser published by unknown_publisher(static) Average Delay: 0 Max Delay: 0 Frame: start_of_service published by unknown_publisher(static) Average Delay: 0 Max Delay: 0 All Broadcasters: Node: unknown_publisher 198.213 Hz, Average Delay: -0.158295 Max Delay: 0 Node: unknown_publisher(static) 198.109 Hz, Average Delay: 0 Max Delay: 0 is that normal there are all named "unknown publisher"? and sometimes during scan,this message pop: Warning: TF_OLD_DATA ignoring data from the past for frame start_of_service at time 1.55437e+09 according to authority unknown_publisher Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained at line 277 in /tmp/binarydeb/ros-kinetic-tf2-0.5.20/src/buffer_core.cpp I tried reset tf from rviz bottom button, but don't see any difference A last thing: In tango ros streamer, I can't acces the setting "enable color camera". Says "requires API >23. Is that why my bag is missing the images? I'm thinking about arduino IMU module to test it's presicion compare to the tango IMU. Do you think that can help? I have doubt about this mapping method. Here we map with the tango IMU precision. That is why I have noise on lidar points (same noise than tango point cloud) while lidar is a very precise device. Can we make the pose estimation in a other way? Is there a way to find features in lidar points to estimate its transform in the 3d world? then check every second if this lidar pose estimation and Tango imu pose are enough close to validate lidar transform and points, to use lidar precision, not IMU precision.Then use images and when RTAB-map find a good loop closure, set Lidar pose estimation and IMU pose at the same location. I read the "RTAB setup with a 3D LiDAR" thread. Is it similar to what I'm thinking? DB from my last test,scan test start at frames 765, shaking IMU at the beginning. https://we.tl/t-NrAWfl2ERG thanks for all your help, results start looking good. cheers. |
Administrator
|
Hi,
I've found that the covariance set for tango odometry is not set, thus the loop closures add more errors in the map than what they can correct. I updated the tutorial. You need to start rtabmap.launch with (based on what I've set for RTAB-Map Tango): odom_tf_linear_variance:=0.0001 odom_tf_angular_variance:=0.000001 At the beginning, the camera is looking straight up toward the ceiling, where there are not a lot of discriminative features, thus Tango is drifting a lot more. Beware that Tango drifts more when the camera is looking textureless (or with very repetitive textures) areas. Those are the point clouds created with only Tango odometry, see how there are multiple layers on the ceiling. It is possible to refine the odometry poses with the laser scans. However, in this database when rotating there is not always a lot of overlap with the previous scan. Increase Rtabmap/DetectionRate to record more frames/scans (if you set it to 0, it would record at 5 Hz matching max tango cloud rate). Also, there is seem to still have not a good synchronization between tango and the lidar. Not sure if it is a timestamp problem (stamps not matching between the devices) or some TF delay somewhere. For the static transform publisher, not sure setting at 200 Hz vs 10 Hz is the solution, as static transforms don't change over time. You may be lucky that time the stamps between Tango and host device were more synchronized. Here is a comparison between tango odometry and when refining using scan matching: In the second image the scans were downsampled for he matching, but we can see that when the scans are matching the tango clouds don't, which means a synchronization/TF problem between lidar and tango. I don't think the arduino IMU would be more accurate than what Tango is using, though you may get a better synchronization with the lidar. With lidar-only + IMU (without tango), you may look at this velodyne example or this ouster example. cheers, Mathieu |
Hi.
I tried to modify the launch file of velodyne exemple but have a lot of errors.don't understand why... please HELP!!! I'm able to get a sensor_msgs/Imu from my mpu6050 with this : roslauch mpu6050_serial_to_imu demo.launch data look ok in Rviz. I launch my lidar: roslaunch quanergy_client_ros client2.launch static transform between imu and Lidar device: rosrun tf static_transform_publisher 0 0 0 0 0 0 imu_link Lidar 100 then : roslaunch rtabmap_ros rtabmap_LidarImu.launchrtabmap_LidarImu.launch have got this msg: roslaunch rtabmap_ros rtabmap_LidarImu.launch ... logging to /home/sdeboffle/.ros/log/fdfbd2bc-6120-11e9-95cf-9829a6388ce0/roslaunch-sdeboffle-Predator-G3-572-30044.log Checking log directory for disk usage. This may take awhile. Press Ctrl-C to interrupt Done checking log file disk usage. Usage is <1GB. started roslaunch server http://sdeboffle-Predator-G3-572:43625/ SUMMARY ======== PARAMETERS * /rosdistro: kinetic * /rosversion: 1.12.14 * /rtabmap/icp_odometry/Icp/CorrespondenceRatio: 0.01 * /rtabmap/icp_odometry/Icp/DownsamplingStep: 1 * /rtabmap/icp_odometry/Icp/Epsilon: 0.001 * /rtabmap/icp_odometry/Icp/Iterations: 10 * /rtabmap/icp_odometry/Icp/MaxCorrespondenceDistance: 1 * /rtabmap/icp_odometry/Icp/MaxTranslation: 2 * /rtabmap/icp_odometry/Icp/PM: true * /rtabmap/icp_odometry/Icp/PMOutlierRatio: 0.7 * /rtabmap/icp_odometry/Icp/PointToPlane: true * /rtabmap/icp_odometry/Icp/PointToPlaneK: 20 * /rtabmap/icp_odometry/Icp/PointToPlaneRadius: 0 * /rtabmap/icp_odometry/Icp/VoxelSize: 0.2 * /rtabmap/icp_odometry/Odom/ScanKeyFrameThr: 0.9 * /rtabmap/icp_odometry/Odom/Strategy: 0 * /rtabmap/icp_odometry/OdomF2M/ScanMaxSize: 15000 * /rtabmap/icp_odometry/OdomF2M/ScanSubtractRadius: 0.2 * /rtabmap/icp_odometry/expected_update_rate: 15.0 * /rtabmap/icp_odometry/frame_id: imu_base * /rtabmap/icp_odometry/odom_frame_id: odom * /rtabmap/point_cloud_assembler/fixed_frame_id: * /rtabmap/point_cloud_assembler/max_clouds: 10 * /rtabmap/rtabmap/Grid/CellSize: 0.1 * /rtabmap/rtabmap/Grid/ClusterRadius: 1 * /rtabmap/rtabmap/Grid/GroundIsObstacle: true * /rtabmap/rtabmap/Grid/RangeMax: 20 * /rtabmap/rtabmap/Icp/CorrespondenceRatio: 0.4 * /rtabmap/rtabmap/Icp/Epsilon: 0.001 * /rtabmap/rtabmap/Icp/Iterations: 10 * /rtabmap/rtabmap/Icp/MaxCorrespondenceDistance: 1 * /rtabmap/rtabmap/Icp/MaxTranslation: 3 * /rtabmap/rtabmap/Icp/PM: true * /rtabmap/rtabmap/Icp/PMOutlierRatio: 0.7 * /rtabmap/rtabmap/Icp/PointToPlane: true * /rtabmap/rtabmap/Icp/PointToPlaneK: 20 * /rtabmap/rtabmap/Icp/PointToPlaneRadius: 0 * /rtabmap/rtabmap/Icp/VoxelSize: 0.2 * /rtabmap/rtabmap/Mem/NotLinkedNodesKept: false * /rtabmap/rtabmap/Mem/STMSize: 30 * /rtabmap/rtabmap/RGBD/AngularUpdate: 0.05 * /rtabmap/rtabmap/RGBD/LinearUpdate: 0.05 * /rtabmap/rtabmap/RGBD/NeighborLinkRefining: false * /rtabmap/rtabmap/RGBD/ProximityBySpace: true * /rtabmap/rtabmap/RGBD/ProximityMaxGraphDepth: 0 * /rtabmap/rtabmap/RGBD/ProximityPathMaxNeighbors: 1 * /rtabmap/rtabmap/Reg/Strategy: 1 * /rtabmap/rtabmap/Rtabmap/DetectionRate: 1 * /rtabmap/rtabmap/approx_sync: False * /rtabmap/rtabmap/frame_id: imu_base * /rtabmap/rtabmap/subscribe_depth: False * /rtabmap/rtabmap/subscribe_rgb: False * /rtabmap/rtabmap/subscribe_scan_cloud: True * /rtabmap/rtabmapviz/approx_sync: False * /rtabmap/rtabmapviz/frame_id: imu_base * /rtabmap/rtabmapviz/odom_frame_id: odom * /rtabmap/rtabmapviz/subscribe_odom_info: True * /rtabmap/rtabmapviz/subscribe_scan_cloud: True NODES /rtabmap/ icp_odometry (rtabmap_ros/icp_odometry) point_cloud_assembler (nodelet/nodelet) rtabmap (rtabmap_ros/rtabmap) rtabmapviz (rtabmap_ros/rtabmapviz) ROS_MASTER_URI=http://localhost:11311 process[rtabmap/icp_odometry-1]: started with pid [30061] process[rtabmap/rtabmap-2]: started with pid [30062] process[rtabmap/rtabmapviz-3]: started with pid [30063] process[rtabmap/point_cloud_assembler-4]: started with pid [30064] type is rtabmap_ros/point_cloud_assembler [ERROR] [1555514311.817525901]: Failed to load nodelet [/rtabmap/point_cloud_assembler] of type [rtabmap_ros/point_cloud_assembler] even after refreshing the cache: According to the loaded plugin descriptions the class rtabmap_ros/point_cloud_assembler with base class type nodelet::Nodelet does not exist. Declared types are depth_image_proc/convert_metric depth_image_proc/crop_foremost depth_image_proc/disparity depth_image_proc/point_cloud_xyz depth_image_proc/point_cloud_xyz_radial depth_image_proc/point_cloud_xyzi depth_image_proc/point_cloud_xyzi_radial depth_image_proc/point_cloud_xyzrgb depth_image_proc/register freenect_camera/driver image_proc/crop_decimate image_proc/crop_nonZero image_proc/crop_non_zero image_proc/debayer image_proc/rectify image_proc/resize image_publisher/image_publisher image_rotate/image_rotate image_view/disparity image_view/image laser_ortho_projector/LaserOrthoProjectorNodelet laser_scan_matcher/LaserScanMatcherNodelet laser_scan_sparsifier/LaserScanSparsifierNodelet laser_scan_splitter/LaserScanSplitterNodelet nodelet_tutorial_math/Plus openni_camera/driver pcl/BAGReader pcl/BoundaryEstimation pcl/ConvexHull2D pcl/CropBox pcl/EuclideanClusterExtraction pcl/ExtractIndices pcl/ExtractPolygonalPrismData pcl/FPFHEstimation pcl/FPFHEstimationOMP pcl/MomentInvariantsEstimation pcl/MovingLeastSquares pcl/NodeletDEMUX pcl/NodeletMUX pcl/NormalEstimation pcl/NormalEstimationOMP pcl/NormalEstimationTBB pcl/PCDReader pcl/PCDWriter pcl/PFHEstimation pcl/PassThrough pcl/PointCloudConcatenateDataSynchronizer pcl/PointCloudConcatenateFieldsSynchronizer pcl/PrincipalCurvaturesEstimation pcl/ProjectInliers pcl/RadiusOutlierRemoval pcl/SACSegmentation pcl/SACSegmentationFromNormals pcl/SHOTEstimation pcl/SHOTEstimationOMP pcl/SegmentDifferences pcl/StatisticalOutlierRemoval pcl/VFHEstimation pcl/VoxelGrid rtabmap_ros/data_odom_sync rtabmap_ros/data_throttle rtabmap_ros/disparity_to_depth rtabmap_ros/icp_odometry rtabmap_ros/obstacles_detection rtabmap_ros/obstacles_detection_old rtabmap_ros/point_cloud_aggregator rtabmap_ros/point_cloud_xyz rtabmap_ros/point_cloud_xyzrgb rtabmap_ros/pointcloud_to_depthimage rtabmap_ros/rgbd_odometry rtabmap_ros/rgbd_sync rtabmap_ros/rgbdicp_odometry rtabmap_ros/rtabmap rtabmap_ros/stereo_odometry rtabmap_ros/stereo_sync rtabmap_ros/stereo_throttle rtabmap_ros/undistort_depth stereo_image_proc/disparity stereo_image_proc/point_cloud2 [ERROR] [1555514311.817609380]: The error before refreshing the cache was: According to the loaded plugin descriptions the class rtabmap_ros/point_cloud_assembler with base class type nodelet::Nodelet does not exist. Declared types are depth_image_proc/convert_metric depth_image_proc/crop_foremost depth_image_proc/disparity depth_image_proc/point_cloud_xyz depth_image_proc/point_cloud_xyz_radial depth_image_proc/point_cloud_xyzi depth_image_proc/point_cloud_xyzi_radial depth_image_proc/point_cloud_xyzrgb depth_image_proc/register freenect_camera/driver image_proc/crop_decimate image_proc/crop_nonZero image_proc/crop_non_zero image_proc/debayer image_proc/rectify image_proc/resize image_publisher/image_publisher image_rotate/image_rotate image_view/disparity image_view/image laser_ortho_projector/LaserOrthoProjectorNodelet laser_scan_matcher/LaserScanMatcherNodelet laser_scan_sparsifier/LaserScanSparsifierNodelet laser_scan_splitter/LaserScanSplitterNodelet nodelet_tutorial_math/Plus openni_camera/driver pcl/BAGReader pcl/BoundaryEstimation pcl/ConvexHull2D pcl/CropBox pcl/EuclideanClusterExtraction pcl/ExtractIndices pcl/ExtractPolygonalPrismData pcl/FPFHEstimation pcl/FPFHEstimationOMP pcl/MomentInvariantsEstimation pcl/MovingLeastSquares pcl/NodeletDEMUX pcl/NodeletMUX pcl/NormalEstimation pcl/NormalEstimationOMP pcl/NormalEstimationTBB pcl/PCDReader pcl/PCDWriter pcl/PFHEstimation pcl/PassThrough pcl/PointCloudConcatenateDataSynchronizer pcl/PointCloudConcatenateFieldsSynchronizer pcl/PrincipalCurvaturesEstimation pcl/ProjectInliers pcl/RadiusOutlierRemoval pcl/SACSegmentation pcl/SACSegmentationFromNormals pcl/SHOTEstimation pcl/SHOTEstimationOMP pcl/SegmentDifferences pcl/StatisticalOutlierRemoval pcl/VFHEstimation pcl/VoxelGrid rtabmap_ros/data_odom_sync rtabmap_ros/data_throttle rtabmap_ros/disparity_to_depth rtabmap_ros/icp_odometry rtabmap_ros/obstacles_detection rtabmap_ros/obstacles_detection_old rtabmap_ros/point_cloud_aggregator rtabmap_ros/point_cloud_xyz rtabmap_ros/point_cloud_xyzrgb rtabmap_ros/pointcloud_to_depthimage rtabmap_ros/rgbd_odometry rtabmap_ros/rgbd_sync rtabmap_ros/rgbdicp_odometry rtabmap_ros/rtabmap rtabmap_ros/stereo_odometry rtabmap_ros/stereo_sync rtabmap_ros/stereo_throttle rtabmap_ros/undistort_depth stereo_image_proc/disparity stereo_image_proc/point_cloud2 [ INFO] [1555514311.893311900]: Initializing nodelet with 8 worker threads. [ INFO] [1555514311.902677763]: Starting node... [ INFO] [1555514311.942507180]: Initializing nodelet with 8 worker threads. [rtabmap/point_cloud_assembler-4] process has died [pid 30064, exit code 255, cmd /opt/ros/kinetic/lib/nodelet/nodelet standalone rtabmap_ros/point_cloud_assembler cloud:=/Lidar/points odom:=odom __name:=point_cloud_assembler __log:=/home/sdeboffle/.ros/log/fdfbd2bc-6120-11e9-95cf-9829a6388ce0/rtabmap-point_cloud_assembler-4.log]. log file: /home/sdeboffle/.ros/log/fdfbd2bc-6120-11e9-95cf-9829a6388ce0/rtabmap-point_cloud_assembler-4*.log [ INFO] [1555514312.069009322]: Starting node... [ INFO] [1555514312.172992836]: Odometry: frame_id = imu_base [ INFO] [1555514312.173019787]: Odometry: odom_frame_id = odom [ INFO] [1555514312.173033680]: Odometry: publish_tf = true [ INFO] [1555514312.173047430]: Odometry: wait_for_transform = true [ INFO] [1555514312.173067609]: Odometry: wait_for_transform_duration = 0.100000 [ INFO] [1555514312.173139877]: Odometry: initial_pose = xyz=0.000000,0.000000,0.000000 rpy=0.000000,-0.000000,0.000000 [ INFO] [1555514312.173153721]: Odometry: ground_truth_frame_id = [ INFO] [1555514312.173164903]: Odometry: ground_truth_base_frame_id = imu_base [ INFO] [1555514312.173178012]: Odometry: config_path = [ INFO] [1555514312.173194892]: Odometry: publish_null_when_lost = true [ INFO] [1555514312.173208083]: Odometry: guess_frame_id = [ INFO] [1555514312.173220369]: Odometry: guess_min_translation = 0.000000 [ INFO] [1555514312.173233581]: Odometry: guess_min_rotation = 0.000000 [ INFO] [1555514312.174117772]: Setting odometry parameter "Icp/CorrespondenceRatio"="0.01" [ INFO] [1555514312.174618341]: Setting odometry parameter "Icp/DownsamplingStep"="1" [ INFO] [1555514312.175160865]: Setting odometry parameter "Icp/Epsilon"="0.001" [ INFO] [1555514312.175613636]: Setting odometry parameter "Icp/Iterations"="10" [ INFO] [1555514312.176102246]: Setting odometry parameter "Icp/MaxCorrespondenceDistance"="1" [ INFO] [1555514312.178271780]: Setting odometry parameter "Icp/MaxTranslation"="2" [ INFO] [1555514312.178677608]: Setting odometry parameter "Icp/PM"="true" [ INFO] [1555514312.191706318]: Setting odometry parameter "Icp/PMOutlierRatio"="0.7" [ INFO] [1555514312.192568108]: Setting odometry parameter "Icp/PointToPlane"="true" [ INFO] [1555514312.193380184]: Setting odometry parameter "Icp/PointToPlaneK"="20" [ INFO] [1555514312.197816617]: Setting odometry parameter "Icp/PointToPlaneRadius"="0" [ INFO] [1555514312.198780124]: Setting odometry parameter "Icp/VoxelSize"="0.2" [ INFO] [1555514312.211238737]: rtabmapviz: Using configuration from "/home/sdeboffle/.ros/rtabmapGUI.ini" [ INFO] [1555514312.259698629]: /rtabmap/rtabmap(maps): map_filter_radius = 0.000000 [ INFO] [1555514312.259727499]: /rtabmap/rtabmap(maps): map_filter_angle = 30.000000 [ INFO] [1555514312.259736922]: /rtabmap/rtabmap(maps): map_cleanup = true [ INFO] [1555514312.259746514]: /rtabmap/rtabmap(maps): map_negative_poses_ignored = true [ INFO] [1555514312.259753965]: /rtabmap/rtabmap(maps): map_negative_scan_ray_tracing = true [ INFO] [1555514312.259762271]: /rtabmap/rtabmap(maps): cloud_output_voxelized = true [ INFO] [1555514312.259772361]: /rtabmap/rtabmap(maps): cloud_subtract_filtering = false [ INFO] [1555514312.259784613]: /rtabmap/rtabmap(maps): cloud_subtract_filtering_min_neighbors = 2 [ INFO] [1555514312.293128468]: /rtabmap/rtabmap(maps): octomap_tree_depth = 16 [ INFO] [1555514312.297185510]: Setting odometry parameter "Odom/ScanKeyFrameThr"="0.9" [ INFO] [1555514312.298022345]: Setting odometry parameter "Odom/Strategy"="0" [ INFO] [1555514312.317890420]: Setting odometry parameter "OdomF2M/ScanMaxSize"="15000" [ INFO] [1555514312.321341007]: Setting odometry parameter "OdomF2M/ScanSubtractRadius"="0.2" [ INFO] [1555514312.335787264]: rtabmap: frame_id = imu_base [ INFO] [1555514312.335829236]: rtabmap: map_frame_id = map [ INFO] [1555514312.335859235]: rtabmap: tf_delay = 0.050000 [ INFO] [1555514312.335874422]: rtabmap: tf_tolerance = 0.100000 [ INFO] [1555514312.335891462]: rtabmap: odom_sensor_sync = false [ INFO] [1555514312.476157012]: Setting RTAB-Map parameter "Grid/CellSize"="0.1" [ INFO] [1555514312.477001271]: Setting RTAB-Map parameter "Grid/ClusterRadius"="1" [ INFO] [1555514312.504080260]: Setting RTAB-Map parameter "Grid/GroundIsObstacle"="true" [ INFO] [1555514312.545899122]: Setting RTAB-Map parameter "Grid/RangeMax"="20" [ INFO] [1555514312.604495626]: Setting RTAB-Map parameter "Icp/CorrespondenceRatio"="0.4" [ INFO] [1555514312.608435758]: Setting RTAB-Map parameter "Icp/Epsilon"="0.001" [ INFO] [1555514312.609170494]: Setting RTAB-Map parameter "Icp/Iterations"="10" [ INFO] [1555514312.609914643]: Setting RTAB-Map parameter "Icp/MaxCorrespondenceDistance"="1" [ INFO] [1555514312.613432797]: Setting RTAB-Map parameter "Icp/MaxTranslation"="3" [ INFO] [1555514312.614141620]: Setting RTAB-Map parameter "Icp/PM"="true" [ INFO] [1555514312.633928455]: Setting RTAB-Map parameter "Icp/PMOutlierRatio"="0.7" [ INFO] [1555514312.634965865]: Setting RTAB-Map parameter "Icp/PointToPlane"="true" [ INFO] [1555514312.637341977]: Setting RTAB-Map parameter "Icp/PointToPlaneK"="20" [ INFO] [1555514312.647675626]: Setting RTAB-Map parameter "Icp/PointToPlaneRadius"="0" [ INFO] [1555514312.648352631]: Setting RTAB-Map parameter "Icp/VoxelSize"="0.2" [ WARN] [1555514312.766584678]: ICP odometry works only with "Reg/Strategy"=1. Ignoring value 0. [ WARN] [1555514312.767251542]: IcpOdometry: Transferring value 0.2 of "Icp/VoxelSize" to ros parameter "scan_voxel_size" for convenience. "Icp/VoxelSize" is set to 0. [ WARN] [1555514312.767951023]: IcpOdometry: Transferring value 20 of "Icp/PointToPlaneK" to ros parameter "scan_normal_k" for convenience. [ WARN] (2019-04-17 17:18:32.768) RegistrationIcp.cpp:423::parseParameters() Parameter Icp/PM is set to true but RTAB-Map has not been built with libpointmatcher support. Setting to false. [ WARN] (2019-04-17 17:18:32.768) OdometryF2M.cpp:133::OdometryF2M() OdomF2M/BundleAdjustment=1 cannot be used with registration not done only with images (Reg/Strategy=1), disabling bundle adjustment. [ INFO] [1555514312.783384651]: IcpOdometry: scan_cloud_max_points = 0 [ INFO] [1555514312.783415488]: IcpOdometry: scan_downsampling_step = 1 [ INFO] [1555514312.783436160]: IcpOdometry: scan_voxel_size = 0.200000 [ INFO] [1555514312.783453463]: IcpOdometry: scan_normal_k = 20 [ INFO] [1555514312.783466239]: IcpOdometry: scan_normal_radius = 0.000000 [ INFO] [1555514312.812208080]: Setting RTAB-Map parameter "Mem/NotLinkedNodesKept"="false" [ INFO] [1555514312.823307821]: Setting RTAB-Map parameter "Mem/STMSize"="30" [ WARN] (2019-04-17 17:18:33.129) RegistrationIcp.cpp:1123::computeTransformationImpl() Maximum laser scans points not set for signature 2, correspondences ratio set relative instead of absolute! This message will only appear once. [ INFO] [1555514313.185166798]: Setting RTAB-Map parameter "RGBD/AngularUpdate"="0.05" [ INFO] [1555514313.201780538]: Setting RTAB-Map parameter "RGBD/LinearUpdate"="0.05" [ INFO] [1555514313.233621032]: Setting RTAB-Map parameter "RGBD/NeighborLinkRefining"="false" [ INFO] [1555514313.235758448]: Setting RTAB-Map parameter "RGBD/OptimizeFromGraphEnd"="false" [ INFO] [1555514313.252823569]: Setting RTAB-Map parameter "RGBD/ProximityBySpace"="true" [ INFO] [1555514313.255546562]: Setting RTAB-Map parameter "RGBD/ProximityMaxGraphDepth"="0" [ INFO] [1555514313.261882255]: Setting RTAB-Map parameter "RGBD/ProximityPathMaxNeighbors"="1" [ INFO] [1555514313.278521238]: Setting RTAB-Map parameter "Reg/Strategy"="1" [ INFO] [1555514313.286187986]: Setting RTAB-Map parameter "Rtabmap/DetectionRate"="1" [ INFO] [1555514313.341116128]: Reading parameters from the ROS server... [ INFO] [1555514313.745444317]: Parameters read = 0 [ WARN] [1555514313.968530510]: Setting "Grid/FromDepth" parameter to false (default true) as "subscribe_scan" or "subscribe_scan_cloud" is true. The occupancy grid map will be constructed from laser scans. To get occupancy grid map from cloud projection, set "Grid/FromDepth" to true. To suppress this warning, add [ INFO] [1555514314.244627339]: RTAB-Map detection rate = 1.000000 Hz [ INFO] [1555514314.244733685]: rtabmap: Deleted database "/home/sdeboffle/.ros/rtabmap.db" (--delete_db_on_start or -d are set). [ INFO] [1555514314.244767448]: rtabmap: Using database from "/home/sdeboffle/.ros/rtabmap.db" (0 MB). [ WARN] (2019-04-17 17:18:34.255) RegistrationIcp.cpp:423::parseParameters() Parameter Icp/PM is set to true but RTAB-Map has not been built with libpointmatcher support. Setting to false. [ WARN] (2019-04-17 17:18:34.255) RegistrationIcp.cpp:423::parseParameters() Parameter Icp/PM is set to true but RTAB-Map has not been built with libpointmatcher support. Setting to false. [ WARN] (2019-04-17 17:18:34.255) RegistrationIcp.cpp:423::parseParameters() Parameter Icp/PM is set to true but RTAB-Map has not been built with libpointmatcher support. Setting to false. [ WARN] (2019-04-17 17:18:34.256) RegistrationIcp.cpp:423::parseParameters() Parameter Icp/PM is set to true but RTAB-Map has not been built with libpointmatcher support. Setting to false. [ WARN] (2019-04-17 17:18:34.273) RegistrationIcp.cpp:423::parseParameters() Parameter Icp/PM is set to true but RTAB-Map has not been built with libpointmatcher support. Setting to false. [ WARN] (2019-04-17 17:18:34.273) RegistrationIcp.cpp:423::parseParameters() Parameter Icp/PM is set to true but RTAB-Map has not been built with libpointmatcher support. Setting to false. [ WARN] [1555514315.402069821]: When subscribing to laser scan, you should subscribe to depth, stereo or rgbd too. Subscribing to depth by default... [ INFO] [1555514315.405255166]: /rtabmap/rtabmapviz: queue_size = 10 [ INFO] [1555514315.405277173]: /rtabmap/rtabmapviz: rgbd_cameras = 1 [ INFO] [1555514315.405289081]: /rtabmap/rtabmapviz: approx_sync = false [ INFO] [1555514315.405328531]: Setup depth callback [ INFO] [1555514315.468613875]: /rtabmap/rtabmapviz subscribed to (exact sync): /rtabmap/rgb/image, /rtabmap/depth/image, /rtabmap/rgb/camera_info, /Lidar/points, /rtabmap/odom_info [ INFO] [1555514315.468690466]: rtabmapviz started. [ WARN] (2019-04-17 17:18:36.996) RegistrationIcp.cpp:423::parseParameters() Parameter Icp/PM is set to true but RTAB-Map has not been built with libpointmatcher support. Setting to false. [ WARN] (2019-04-17 17:18:36.996) RegistrationIcp.cpp:423::parseParameters() Parameter Icp/PM is set to true but RTAB-Map has not been built with libpointmatcher support. Setting to false. [ INFO] [1555514316.997212927]: rtabmap: Database version = "0.17.6". [ INFO] [1555514317.061885206]: /rtabmap/rtabmap: queue_size = 10 [ INFO] [1555514317.061938733]: /rtabmap/rtabmap: rgbd_cameras = 1 [ INFO] [1555514317.061967233]: /rtabmap/rtabmap: approx_sync = false [ INFO] [1555514317.062069354]: Setup rgbd callback [ INFO] [1555514317.079972646]: /rtabmap/rtabmap subscribed to (exact sync): /rtabmap/odom, /rtabmap/rgbd_image, /rtabmap/assembled_cloud [ INFO] [1555514317.091830951]: rtabmap 0.17.6 started... [ WARN] [1555514320.468843538]: /rtabmap/rtabmapviz: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called. /rtabmap/rtabmapviz subscribed to (exact sync): /rtabmap/rgb/image, /rtabmap/depth/image, /rtabmap/rgb/camera_info, /Lidar/points, /rtabmap/odom_info [ WARN] [1555514322.080151674]: /rtabmap/rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called. /rtabmap/rtabmap subscribed to (exact sync): /rtabmap/odom, /rtabmap/rgbd_image, /rtabmap/assembled_cloud [ WARN] [1555514325.469064554]: /rtabmap/rtabmapviz: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called. /rtabmap/rtabmapviz subscribed to (exact sync): /rtabmap/rgb/image, /rtabmap/depth/image, /rtabmap/rgb/camera_info, /Lidar/points, /rtabmap/odom_info ^C[rtabmap/rtabmapviz-3] killing on exit [ INFO] [1555514325.949639405]: rtabmapviz: ctrl-c catched! Exiting Qt app... [rtabmap/rtabmap-2] killing on exit [rtabmap/icp_odometry-1] killing on exit rtabmap: Saving database/long-term memory... (located at /home/sdeboffle/.ros/rtabmap.db) rtabmap: Saving database/long-term memory...done! (located at /home/sdeboffle/.ros/rtabmap.db, 0 MB) shutting down processing monitor... ... shutting down processing monitor complete done is my rtab-map installation is corrut? thanks |
Administrator
|
Hi,
You need latest rtabmap version built from source to make it work (as it is a recent addon). rtabmap binaries should be uninstalled, libpointmatcher should be installed for this lidar example, then rebuild rtabmap (make sure you see "-- *With libpointmatcher = YES (License: BSD)" when doing cmake part of rtabmap. See https://github.com/introlab/rtabmap_ros#build-from-source for details. cheers, Mathieu |
hi mathieu.
All is working well after uninstall and rebuild from source, thanks. I modified velodyne launch file to match my datas. That's looks far more precise than with the tango method. MPU6050 look better than tango imu (checked each in rviz, tango shake a lot more). first database test : https://wetransfer.com/downloads/809796c167f93a97969cd1b655d119b620190418122150/4208ca896320909dd87a71b82fc6bf6620190418122150/617b00 my launch sequence: roscore roslaunch mpu6050_serial_to_imu demo.launch roslaunch quanergy_client_ros client2.launch rosrun tf static_transform_publisher 0 0 0 0 0 0 imu_base Lidar 100 roslaunch rtabmap_ros rtabmap_LidarImu.launch with rtabmap_LidarImu.launch: rtabmap_LidarImu.launch is my imu-->Lidar tf static transform look logical to you? Is it better to use imu_base or imu_link? is there a way to add a kinect to that setup?Is there a advantage to do so, for visual loop closure? After a couple a minuts, rtab starts to be very slow, how to make it run better for long time scan? (tried to increase Icp/VoxelSize but no results) I tried to modify the Kinect + Odometry + 2D laser (setup your robot) tutorial for my setup but get that msgs: [ WARN] [1555599958.490518678]: /rtabmap/rgbd_sync: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. /rtabmap/rgbd_sync subscribed to (approx sync): /camera/rgb/image_rect_color, /camera/depth_registered/image_raw, /camera/rgb/camera_info cheers, Stephane |
Administrator
|
Hi,
Voxel size of 2 meters seem high to me as it is 20 cm in the velodyne example. If you want to save time and memory, uncomment those lines: <!-- param name="Mem/LaserScanVoxelSize" type="string" value="0.1"/ --> <!-- param name="Mem/LaserScanNormalK" type="string" value="10"/ --> <!-- param name="Mem/LaserScanRadius" type="string" value="0"/ -->and comment this one under rtabmap node: <param name="Icp/VoxelSize" type="string" value="2"/> In that setup you don't seem using the IMU (use_imu argument is false), I recommend to use one if available. For the transform IMU->lidar, the orientation should be accurate. For example, make sure the imu frame matches the lidar frame. The odometry seems drifting quite a lot, can you share a rosbag (lidar, tf, imu)? It would be easier to debug. You can use a kinect at the same time. The rgbd_sync approach is indeed to way to go. The warning here is that rgbd_sync didn't receive any kinect data. Verify kinect topics are published: $ rosrun topic hz /camera/rgb/image_rect_color /camera/depth_registered/image_raw /camera/rgb/camera_info cheers, Mathieu |
Hi,
Sorry for the Icp/voxelSize value. That was my last test (not the one I send), not the best results. so if I add: <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="screen"> <remap from="rgb/image" to="/camera/rgb/image_rect_color"/> <remap from="depth/image" to="/camera/depth_registered/image_raw"/> <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/> <remap from="rgbd_image" to="rgbd_image"/> </node> at the beginning of my file, that should work? for the camera topics, I checked them in Rviz, and I can see them. I use Freenect. I will try those changes tomorrow. cheers Stephane |
Administrator
|
Yes, and for rtabmap node, set "subscribe_rgbd" to true and remap rgbd_image topic if needed.
|
hi.
I think I had some kinect drivers issues. I reinstall it, and now all topics are published.
now it's a other error:
[ INFO] [1555687462.966648576]: Odom: ratio=0.245394, std dev=0.001585m|0.001585rad, update time=1.454655s
[ INFO] [1555687464.427559120]: Odom: ratio=0.240180, std dev=0.001576m|0.001576rad, update time=1.445957s
[ INFO] [1555687465.925904932]: Odom: ratio=0.242494, std dev=0.001599m|0.001599rad, update time=1.482368s
[ WARN] [1555687466.392625679]: /rtabmap/rtabmapviz: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called.
/rtabmap/rtabmapviz subscribed to (exact sync):
/Lidar/points,
/rtabmap/odom_info
[ INFO] [1555687467.388982669]: Odom: ratio=0.243336, std dev=0.001566m|0.001566rad, update time=1.442059s
[ WARN] [1555687467.748107115]: /rtabmap/rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=100).
/rtabmap/rtabmap subscribed to (approx sync):
/rtabmap/odom,
/rtabmap/rgbd_image,
/rtabmap/assembled_cloud
I think I made a mistake in my launch file but don't understand where.
rtabmap_LidarImu.launch
if you have an idea...
cheers
stephane
|
Hi,
I found my mistake. Don't add the rgbd_sync at the right place. My launch file look like this: LidarImuKinect01.launch |
Hi,
I made some tests last few days, and the setup is doing great job. except for one zone of my office.I think it's append when I pass through a door, visual odometry is broken. is it a limitations?Is there some setting wrong in my launch file? Can you check my database to see if you can improve final results? https://wetransfer.com/downloads/5d7673c7503a241ac8a1462d5512566920190426153428/15cad83f45f4babfee89f4d852756a1420190426153428/b656e1 LidarImuKinect01.launch Thanks, I now have a device making me scan 10 times faster than with a faro scanner with a better precision than the tango. cheers, stephane |
Administrator
|
Hi Stephane,
Looking at the generated point cloud from laser scans, there are strange overlapping walls (see section inside blue rectangle): I looked in the database and all links are pretty good. The problem here is the glass wall in the right room. There an example of single scan and corresponding RGB view: see how the glass wall we see in RGB image is causing reflections in the scan (doubling the room behind the glass wall), shown in blue rectange on right top view of the scans (the green triangle is the camera frustum): This kind of situation (e.g., glass, windows, reflective surfaces) is causing the mirroring room problem as seen in the first image of this post. Ideally, it would be nice to select those points behind the wall in DatabaseViewer and delete them, so they are not added to global map afterwards. However, that feature is only implemented with depth images (like removing mirrors in this tutorial)... Another problem in the database: the TF between camera and lidar seems a little off in "yaw", so the walls in RGB-D image doesn't match the walls in the scan: EDIT For your question: You may try traversing backward the doors, so that the scans can still be registered with the previous ones. cheers, Mathieu |
hi,
you reply to my question with the "mirror effect". I thought that error in point cloud was due to visual odometry error, but your answer explain all my problem. I tried to reject all "space proximity"loop closure with the database editor and check all remaining visual loop closure but no change. That's why. Thanks. For the tf between lidar and camera, I think the kinect move gently at a time between my tests. I have to fix it better to the lidar but I wanted to have good results before that. Even with this yaw error, kinect cloud should be good, no? With a little rotation in cloud compare,it should superpose with lidar cloud. Many thanks to you. I'm clearly not a expert of ROS environment, or SLAM technology and my coding knowledge are limited (as my english vocabulary) but you make me able to do great things. YOU ROCK!!! I can't reopen db on my desktop due to version. Do you plan to build a v19 for windows?or do you have a trick to open a v19 db in v18 standelone rtabmap? :) |
Administrator
|
Hi Stephane,
The kinect clouds will appear with a small angle error against the lidar point cloud. The position would be good, but not the rotation of each individual kinect frame. Even if you say you are not an expert in ROS, you have done great so far. I was waiting to stabilize 0.19 before officially releasing it. You can however get it through the windows build farm here: https://ci.appveyor.com/project/matlabbe/rtabmap/branch/master/artifacts cheers, Mathieu |
Free forum by Nabble | Edit this page |