Mapping with KnectV2 and Husky A200

classic Classic list List threaded Threaded
6 messages Options
Reply | Threaded
Open this post in threaded view
|

Mapping with KnectV2 and Husky A200

ricardo
Hi Mathieu;

I'm working on Husky A200 + Kinect V2 + laser LMS111. I create a simulation on gazebo to reproduce the tutorial 2.1http://wiki.ros.org/rtabmap_ros/Tutorials/SetupOnYourRobot#Kinect_.2B-_Odometry_.2B-_2D_laser. In the simulation, everything works perfectly. I download the model into catkin_ws and make it. After I just change the robot description to include the xacro and them everything went ok.

Now I'm using the real robot with this TF tree.
Robot TF
To launch the camera drivers

1
roslaunc kinect2_bridge my_bridge.launch publish_tf:=true 
and it's tf is created. To "attach" the camera TF to robot TF, I created two static transforms inside of my_bridge.launch as below
<node pkg="tf" type="static_transform_publisher" name="kinect_to_base_link" args="0.3206 0.000 0.299635 0 0 0 /top_plate_link /kinect2  100"/>

<node pkg="tf" type="static_transform_publisher" name="kinect2_to_kinect2_link" args="0 0 0 0 0 0 /kinect2 /kinect2_link 100"/>

For RTAB I used the example code in the tutorial 2.1 with modification to get the map through RGB-D sensor
 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
<launch>
  <group ns="rtabmap">

    <!-- Use RGBD synchronization -->
    <!-- Here is a general example using a standalone nodelet, 
         but it is recommended to attach this nodelet to nodelet 
         manager of the camera to avoid topic serialization -->
    <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="screen">
      <remap from="rgb/image"       to="/kinect2/sd/image_color_rect"/>
      <remap from="depth/image"     to="/kinect2/sd/image_depth_rect"/>
      <remap from="rgb/camera_info" to="/kinect2/sd/camera_info"/>
      <remap from="rgbd_image"      to="rgbd_image"/> <!-- output -->
      
      <!-- Should be true for not synchronized camera topics 
           (e.g., false for kinectv2, zed, realsense, true for xtion, kinect360)-->
      <param name="approx_sync"       value="false"/> 
    </node>

    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
          <param name="frame_id" type="string" value="base_link"/>

          <param name="subscribe_depth" type="bool" value="false"/>
          <param name="subscribe_rgbd" type="bool" value="true"/>
          <param name="subscribe_scan" type="bool" value="true"/>

          <remap from="odom" to="/husky_velocity_controller/odom"/>
          <remap from="scan" to="/scan"/>
          <remap from="rgbd_image" to="rgbd_image"/>

          <param name="queue_size" type="int" value="10"/>

          <!-- RTAB-Map's parameters -->
          <param name="RGBD/NeighborLinkRefining" type="string" value="true"/>
          <param name="RGBD/ProximityBySpace"     type="string" value="true"/>
          <param name="RGBD/AngularUpdate"        type="string" value="0.01"/>
          <param name="RGBD/LinearUpdate"         type="string" value="0.01"/>
          <param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
          <param name="Grid/FromDepth"            type="string" value="true"/> <!-- occupancy grid from lidar -->
          <param name="Reg/Force3DoF"             type="string" value="true"/>
          <param name="Reg/Strategy"              type="string" value="1"/> <!-- 1=ICP -->
          
          <!-- ICP parameters -->
          <param name="Icp/VoxelSize"                 type="string" value="0.05"/>
          <param name="Icp/MaxCorrespondenceDistance" type="string" value="0.1"/>
    </node>
  </group>
</launch>

Now I have the TF from kinect attached to robot TF as below TF robot+kinect
With this setup, the produced map is different from what I expected. The below image shows the obtained map
Map
Do you know what I could have done to not get the correct map?
thank you
Best Regards

Reply | Threaded
Open this post in threaded view
|

Re: Mapping with KnectV2 and Husky A200

matlabbe
Administrator
Hi,

there is maybe a missing optical rotation on the kinect2, which is thinking it is looking up. Like in this example, you would have to change:
<node pkg="tf" type="static_transform_publisher" name="kinect2_to_kinect2_link" args="0 0 0 0 0 0 /kinect2 /kinect2_link 100"/>
by
<node pkg="tf" type="static_transform_publisher" name="kinect2_to_kinect2_link" args="0 0 0 -1.5707963267948966 0 -1.5707963267948966 /kinect2 /kinect2_link 100"/>

You can also open RVIZ, set the global fixed frame to map, and show kinect2 point cloud to see if it is correctly oriented.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Mapping with KnectV2 and Husky A200

ricardo
This post was updated on .
Hi Mathieu Thank you for the advice. The system is now working. However, the obtained map very different that i got through simulation. Here is the map obtained with above configuration.
Real system
and here is the map obtained with the simulation system (tutorial 2.1)
Simulated System
Here is the RTAB-Map parameters collected from terminal:
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
SUMMARY
========

PARAMETERS
 * /rosdistro: kinetic
 * /rosversion: 1.12.14
 * /rtabmap/rgbd_sync/approx_sync: False
 * /rtabmap/rtabmap/Grid/FromDepth: true
 * /rtabmap/rtabmap/Icp/MaxCorrespondenceDistance: 0.1
 * /rtabmap/rtabmap/Icp/VoxelSize: 0.05
 * /rtabmap/rtabmap/RGBD/AngularUpdate: 0.01
 * /rtabmap/rtabmap/RGBD/LinearUpdate: 0.01
 * /rtabmap/rtabmap/RGBD/NeighborLinkRefining: true
 * /rtabmap/rtabmap/RGBD/OptimizeFromGraphEnd: false
 * /rtabmap/rtabmap/RGBD/ProximityBySpace: true
 * /rtabmap/rtabmap/Reg/Force3DoF: true
 * /rtabmap/rtabmap/Reg/Strategy: 1
 * /rtabmap/rtabmap/frame_id: top_plate_link
 * /rtabmap/rtabmap/queue_size: 10
 * /rtabmap/rtabmap/subscribe_depth: True
 * /rtabmap/rtabmap/subscribe_rgbd: True
 * /rtabmap/rtabmap/subscribe_scan: True

NODES
  /rtabmap/
    rgbd_sync (nodelet/nodelet)
    rtabmap (rtabmap_ros/rtabmap)

ROS_MASTER_URI=http://192.168.13.100:11311/

process[rtabmap/rgbd_sync-1]: started with pid [20379]
type is rtabmap_ros/rgbd_sync
process[rtabmap/rtabmap-2]: started with pid [20380]
[ INFO] [1590177836.563486079]: Starting node...
[ INFO] [1590177836.673955376]: Initializing nodelet with 4 worker threads.
[ INFO] [1590177836.857151238]: /rtabmap/rgbd_sync: approx_sync = false
[ INFO] [1590177836.857220276]: /rtabmap/rgbd_sync: queue_size  = 10
[ INFO] [1590177836.857250298]: /rtabmap/rgbd_sync: depth_scale = 1.000000
[ INFO] [1590177836.857269689]: /rtabmap/rgbd_sync: compressed_rate = 0.000000
[ INFO] [1590177836.886067406]: 
/rtabmap/rgbd_sync subscribed to (exact sync):
   /kinect2/sd/image_color_rect,
   /kinect2/sd/image_depth_rect,
   /kinect2/sd/camera_info
[ INFO] [1590177836.913046528]: /rtabmap/rtabmap(maps): map_filter_radius          = 0.000000
[ INFO] [1590177836.913140696]: /rtabmap/rtabmap(maps): map_filter_angle           = 30.000000
[ INFO] [1590177836.913196692]: /rtabmap/rtabmap(maps): map_cleanup                = true
[ INFO] [1590177836.913233609]: /rtabmap/rtabmap(maps): map_always_update          = false
[ INFO] [1590177836.913263941]: /rtabmap/rtabmap(maps): map_empty_ray_tracing      = true
[ INFO] [1590177836.913287242]: /rtabmap/rtabmap(maps): cloud_output_voxelized     = true
[ INFO] [1590177836.913309540]: /rtabmap/rtabmap(maps): cloud_subtract_filtering   = false
[ INFO] [1590177836.913332604]: /rtabmap/rtabmap(maps): cloud_subtract_filtering_min_neighbors = 2
[ INFO] [1590177836.917682623]: /rtabmap/rtabmap(maps): octomap_tree_depth         = 16
[ INFO] [1590177836.966097246]: rtabmap: frame_id      = top_plate_link
[ INFO] [1590177836.966196950]: rtabmap: map_frame_id  = map
[ INFO] [1590177836.966246980]: rtabmap: use_action_for_goal  = false
[ INFO] [1590177836.966292173]: rtabmap: tf_delay      = 0.050000
[ INFO] [1590177836.966331146]: rtabmap: tf_tolerance  = 0.100000
[ INFO] [1590177836.966367934]: rtabmap: odom_sensor_sync   = false
[ INFO] [1590177837.170553867]: Setting RTAB-Map parameter "Grid/FromDepth"="true"
[ INFO] [1590177837.277696257]: Setting RTAB-Map parameter "Icp/MaxCorrespondenceDistance"="0.1"
[ INFO] [1590177837.315495865]: Setting RTAB-Map parameter "Icp/VoxelSize"="0.05"
[ INFO] [1590177837.650638781]: Setting RTAB-Map parameter "RGBD/AngularUpdate"="0.01"
[ INFO] [1590177837.666987274]: Setting RTAB-Map parameter "RGBD/LinearUpdate"="0.01"
[ INFO] [1590177837.705740018]: Setting RTAB-Map parameter "RGBD/NeighborLinkRefining"="true"
[ INFO] [1590177837.709571343]: Setting RTAB-Map parameter "RGBD/OptimizeFromGraphEnd"="false"
[ INFO] [1590177837.742256749]: Setting RTAB-Map parameter "RGBD/ProximityBySpace"="true"
[ INFO] [1590177837.772911289]: Setting RTAB-Map parameter "Reg/Force3DoF"="true"
[ INFO] [1590177837.776509714]: Setting RTAB-Map parameter "Reg/Strategy"="1"
[ INFO] [1590177838.704111941]: Setting "Grid/RangeMax" parameter to 0 (default 5.000000) as "subscribe_scan" or "subscribe_scan_cloud" is true.
[ WARN] [1590177838.704257801]: Setting "RGBD/ProximityPathMaxNeighbors" parameter to 10 (default 0) as "subscribe_scan" is true and "Reg/Strategy" uses ICP. Proximity detection by space will be also done by merging close scans. To disable, set "RGBD/ProximityPathMaxNeighbors" to 0. To suppress this warning, add <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/>
[ INFO] [1590177839.137091435]: RTAB-Map detection rate = 1.000000 Hz
[ INFO] [1590177839.182593618]: rtabmap: Deleted database "/home/administrator/.ros/rtabmap.db" (--delete_db_on_start or -d are set).
[ INFO] [1590177839.182959712]: rtabmap: Using database from "/home/administrator/.ros/rtabmap.db" (0 MB).
[ INFO] [1590177839.347732377]: rtabmap: Database version = "0.19.3".
[ WARN] [1590177839.383623428]: rtabmap: Parameters subscribe_depth and subscribe_rgbd cannot be true at the same time. Parameter subscribe_depth is set to false.
[ INFO] [1590177839.388129641]: /rtabmap/rtabmap: subscribe_depth = false
[ INFO] [1590177839.388287413]: /rtabmap/rtabmap: subscribe_rgb = false
[ INFO] [1590177839.388387198]: /rtabmap/rtabmap: subscribe_stereo = false
[ INFO] [1590177839.388475195]: /rtabmap/rtabmap: subscribe_rgbd = true (rgbd_cameras=1)
[ INFO] [1590177839.388557394]: /rtabmap/rtabmap: subscribe_odom_info = false
[ INFO] [1590177839.388633743]: /rtabmap/rtabmap: subscribe_user_data = false
[ INFO] [1590177839.388707971]: /rtabmap/rtabmap: subscribe_scan = true
[ INFO] [1590177839.388782165]: /rtabmap/rtabmap: subscribe_scan_cloud = false
[ INFO] [1590177839.388856301]: /rtabmap/rtabmap: queue_size    = 10
[ INFO] [1590177839.388933775]: /rtabmap/rtabmap: approx_sync   = true
[ INFO] [1590177839.389073874]: Setup rgbd callback
[ INFO] [1590177839.422369675]: 
/rtabmap/rtabmap subscribed to (approx sync):
   /odometry/filtered,
   /rtabmap/rgbd_image,
   /scan
[ INFO] [1590177839.454807570]: rtabmap 0.19.3 started...
[ WARN] [1590177839.836419052]: /proj_map topic is deprecated! Subscribe to /grid_map topic instead.
[ INFO] [1590177839.837598498]: rtabmap (1): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1620s, Maps update=0.0007s pub=0.0010s (local map=1, WM=1)
[ INFO] [1590177841.011523659]: rtabmap (2): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1884s, Maps update=0.0278s pub=0.0000s (local map=1, WM=1)
[ INFO] [1590177841.960428170]: rtabmap (3): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1941s, Maps update=0.0360s pub=0.0000s (local map=1, WM=1)
[ INFO] [1590177843.033488681]: rtabmap (4): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1499s, Maps update=0.0264s pub=0.0000s (local map=1, WM=1)
^C[rtabmap/rtabmap-2] killing on exit
[rtabmap/rgbd_sync-1] killing on exit
rtabmap: Saving database/long-term memory... (located at /home/administrator/.ros/rtabmap.db)
rtabmap: 2D occupancy grid map saved.
rtabmap: Saving database/long-term memory...done! (located at /home/administrator/.ros/rtabmap.db, 1 MB)
shutting down processing monitor...
... shutting down processing monitor complete
done

Is there anything that I can do to improve the map quality?
*******************************************************************
*******************************************************************
EDIT
******************************************************************
*******************************************************************
I switched the odometry. Previously I was using the odometry from wheel encoders, now I'm using the odometry combined from IMU and well encoders. Due to this I got a better map.

But steel far from what I expect and have many outliers.
Reply | Threaded
Open this post in threaded view
|

Re: Mapping with KnectV2 and Husky A200

matlabbe
Administrator
Hi,

Your odometry may be drifting a lot more in reality than in simulation. However, I see that you are using RGBD/NeighborLinkRefining=true with a lidar. Try with Grid/FromDepth=false to see if the lidar map looks good. Do you have a database to share? If the map with lidar doesn't look good (it should be similar than you have in simluation), ICP/ parameters may need some tuning. If the lidar map is good, it means that the TF between the lidar and camera may be wrong, e.g., if you show scan and camera point cloud in RVIZ, do they match perfectly?

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Mapping with KnectV2 and Husky A200

ricardo
Hi Mathieu

Sorry for the delay.

A create a data base to share with you.

This link contain the full data recorded(13GB)
 https://drive.google.com/file/d/1eRwzcTtlKeig2A2VhNUyGqd_1f73G-aW/view?usp=sharing 

This link contain the same database but compressed ( rosbag compress ....) (3GB)

https://drive.google.com/file/d/1kEp3Hyv4oVQj7js_rvdnCiVf-PF0wHmh/view?usp=sharing

I'm focusing exclusively on mapping mode.
Using this database I generated a map. However, there are many places that were marked as occupied even though it was free.

another quick question: How did you generate your bagfile? It's so small!!! My database is around 13GB/3GB and I only made a few turns with my robot.

thakyou!
Reply | Threaded
Open this post in threaded view
|

Re: Mapping with KnectV2 and Husky A200

matlabbe
Administrator
Hi,

It seems the lidar scan and camera cloud are not perfectly aligned together (it would require some tuning about the static TF, show both the camera cloud and lidar scan in RVIZ, set base_link as the fixed frame in global options):


When correcting odometry based on lidar, the lidar map looks pretty crisp (see below), but the corresponding 3D map from the camera has large walls. Here are two examples.

Grid map created from camera:
$ roslaunch rtabmap_ros rtabmap.launch \
   args:="-d \
      --Reg/Force3DoF true \
      --RGBD/NeighborLinkRefining true \
      --Grid/FromDepth true \
      --Reg/Strategy 1 \
      --Grid/MinGroundHeight -1  \
      --Grid/MaxObstacleHeight 2  \
      --Grid/RangeMax 5" \
   rgb_topic:=/kinect2/sd/image_color_rect \
   depth_topic:=/kinect2/sd/image_depth_rect \
   camera_info_topic:=/kinect2/sd/camera_info \
   visual_odometry:=false \
   odom_topic:=/odometry/filtered \
   rgbd_sync:=true \
   use_sim_time:=true \
   frame_id:=base_link \
   scan_topic:="/scan" \
   subscribe_scan:=true \
   approx_rgbd_sync:=false


Grid map created from lidar:
$ roslaunch rtabmap_ros rtabmap.launch \
   args:="-d \
      --Reg/Force3DoF true \
      --RGBD/NeighborLinkRefining true \
      --Grid/FromDepth false \
      --Reg/Strategy 1" \
   rgb_topic:=/kinect2/sd/image_color_rect \
   depth_topic:=/kinect2/sd/image_depth_rect \
   camera_info_topic:=/kinect2/sd/camera_info \
   visual_odometry:=false \
   odom_topic:=/odometry/filtered \
   rgbd_sync:=true \
   use_sim_time:=true \
   frame_id:=base_link \
   scan_topic:="/scan" \
   subscribe_scan:=true \
   approx_rgbd_sync:=false



Other problems:
1) Sometimes the camera is generating depth values very close to camera. This could be filtered with Grid/RangeMin to 0.5.


2) The RGB and depth is not always aligned, this could affect localization accuracy, though here we refine with lidar, so those errors would be corrected (see how texture doesn't match with depth edges).


3) With iai_kinect2, I prefer to use qhd topics instead of sd topics, because sd introduces fake features because of the black pixels.


About the size of the rosbag, do you mean that demo_mapping.bag? We recorded compressed images at lower frame rate. When visual odometry doesn't have to be computed, we can reduce frame rate to 2-5 Hz for the camera. In your bag, you also recorded /kinect2/sd/points and /scan_inv that are not needed for rtabmap.

cheers,
Mathieu