mapping with kinect v2 + laser scan

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

mapping with kinect v2 + laser scan

ricardo
Hi matlabbe; I`m working on RTAB-MAp with Kinect v2 and Hokuyo URG-04LX laser scan. I followed the hand held camera tutorial and it works fine. Now I`m trying to map using the laser and de rgb-d sensor. the sequence of commands are
$ roscore
$ roslaunch urg_node urg_lidar.launch
$ roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true
$ roslaunch my_rtabmap demo_rtabmap.launch 
the launch file for the hokuyo laser
<launch>

  <node name="urg_node" pkg="urg_node" type="urg_node" output="screen">
    <param name="ip_address" value=""/>
    <param name="serial_port" value="/dev/ttyACM0"/>
    <param name="serial_baud" value="115200"/>
    <param name="calibrate_time" value="true"/>
    <param name="publish_intensity" value="false"/>
    <param name="publish_multiecho" value="false"/>
    <param name="angle_min" value="-1.5707963"/>
    <param name="angle_max" value="1.5707963"/>
    <param name="pub_map_odom_transform" value="true"/>
	<param name="frame_id" value="laser"/>
    <param name="map_frame" value="map" />
    <param name="base_frame" value="laser" />
    
  </node>

</launch>
launch file for my demo
<launch>

 
  <!-- Choose visualization -->
  <arg name="rviz" default="true" />
  <arg name="rtabmapviz" default="false" />
  
  <!-- Choose hector_slam or icp_odometry for odometry -->
  <arg name="hector" default="true" />

  <param name="use_sim_time" type="bool" value="false"/>
  
  <node if="$(arg hector)" pkg="tf" type="static_transform_publisher" name="scanmatcher_to_base_footprint" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /scanmatcher_frame /base_footprint 100" />

  <!-- Odometry from laser scans -->
  <!-- If argument "hector" is true, we use Hector mapping to generate odometry for us -->
  <node if="$(arg hector)" pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
    
    <!-- Frame names -->
    <param name="map_frame" value="hector_map" />
    <param name="base_frame" value="base_footprint" />
    <param name="odom_frame" value="odom" />
    
    <!-- Tf use -->
    <param name="pub_map_odom_transform" value="false"/>
    <param name="pub_map_scanmatch_transform" value="true"/>
    <param name="pub_odometry" value="true"/>
    
    <!-- Map size / start point -->
    <param name="map_resolution" value="0.050"/>
    <param name="map_size" value="2048"/>
    <param name="map_multi_res_levels" value="2" />
    
    <!-- Map update parameters -->
    <param name="map_update_angle_thresh" value="0.06" />
    
    <!-- Advertising config --> 
    <param name="scan_topic" value="/scan"/>
  </node>
  
  <!-- If argument "hector" is false, we use rtabmap's icp odometry to generate odometry for us -->
  <node unless="$(arg hector)" pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="screen" >
     <remap from="scan"      to="/scan"/>
     <remap from="odom"      to="/scanmatch_odom"/>
     <remap from="odom_info"      to="/rtabmap/odom_info"/>
	  
     <param name="frame_id"        type="string" value="base_footprint"/>   
     
     <param name="Icp/PointToPlane"  type="string" value="true"/>
     <param name="Icp/VoxelSize"     type="string" value="0.05"/>
     <param name="Icp/Epsilon"       type="string" value="0.001"/>
     <param name="Icp/PointToPlaneK"  type="string" value="5"/>
     <param name="Icp/PointToPlaneRadius"  type="string" value="0.3"/>
     <param name="Icp/MaxCorrespondenceDistance" type="string" value="0.1"/>
     <param name="Icp/PM"             type="string" value="true"/> <!-- use libpointmatcher to handle PointToPlane with 2d scans-->
     <param name="Icp/PMOutlierRatio" type="string" value="0.95"/>
     <param name="Odom/Strategy"        type="string" value="0"/>
     <param name="Odom/GuessMotion"     type="string" value="true"/>
     <param name="Odom/ResetCountdown"  type="string" value="0"/>
     <param name="Odom/ScanKeyFrameThr"  type="string" value="0.9"/>
  </node>

  <group ns="rtabmap">
    <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/compressed"/>
      <remap from="depth/image"     to="/kinect2/sd/image_depth_rect/compressed"/>
      <remap from="rgb/camera_info" to="/kinect2/sd/camera_info"/>
      
      <param name="rgb/image_transport"   type="string" value="compressed"/>
      <param name="depth/image_transport" type="string" value="compressedDepth"/>
    </node>

    <!-- SLAM -->
    <!-- args: "delete_db_on_start" and "udebug" -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
      <param name="frame_id" type="string" value="base_footprint"/>
	
      <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="scan" to="/scan"/>

      <!-- As hector doesn't provide compatible covariance in the odometry topic, don't use the topic and fix the covariance -->
      <param if="$(arg hector)" name="odom_frame_id"            type="string" value="hector_map"/>
      <param if="$(arg hector)" name="odom_tf_linear_variance"  type="double" value="0.0005"/>
      <param if="$(arg hector)" name="odom_tf_angular_variance" type="double" value="0.0005"/>

      <remap unless="$(arg hector)" from="odom" to="/scanmatch_odom"/>
      <param unless="$(arg hector)" name="subscribe_odom_info" type="bool" value="true"/>
	
      <!-- RTAB-Map's parameters -->
      <param name="Reg/Strategy"       type="string" value="1"/>    <!-- 0=Visual, 1=ICP, 2=Visual+ICP -->
      <param name="Reg/Force3DoF"      type="string" value="true"/>
      <param name="RGBD/ProximityBySpace"      type="string" value="false"/>
    </node>
    
    <!-- Visualisation RTAB-Map -->
    <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
      <param name="subscribe_rgbd"      type="bool" value="false"/>
      <param name="subscribe_laserScan" type="bool" value="true"/>
      <param name="frame_id"            type="string" value="base_footprint"/>
    
      <remap from="scan"            to="/scan"/>

      <!-- As hector doesn't provide compatible covariance in the odometry topic -->
      <param if="$(arg hector)" name="odom_frame_id" type="string" value="hector_map"/>

      <remap unless="$(arg hector)" from="odom" to="/scanmatch_odom"/>
      <param unless="$(arg hector)" name="subscribe_odom_info" type="bool" value="true"/>
    </node>
  
  </group>
  
  <!-- Visualisation RVIZ -->
  <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(find rtabmap_ros)/launch/config/demo_robot_mapping.rviz" output="screen"/>
   <node pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb">
    <remap from="rgbd_image"      to="/rtabmap/rgbd_image"/>
    <remap from="cloud"           to="voxel_cloud" />

    <param name="voxel_size" type="double" value="0.01"/>
  </node>

</launch>
However I cant achieve any results. My terminal keep posting messages like this:
[ WARN] [1573075085.488619475]: /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):
   /kinect2/sd/image_color_rect/compressed/compressed,
   /kinect2/sd/image_depth_rect/compressed/compressedDepth,
   /kinect2/sd/camera_info
[ INFO] [1573075085.576962375]: lookupTransform base_footprint to laser timed out. Could not transform laser scan into base_frame.
[ INFO] [1573075086.079350690]: lookupTransform base_footprint to laser timed out. Could not transform laser scan into base_frame.
[ INFO] [1573075086.582101596]: lookupTransform base_footprint to laser timed out. Could not transform laser scan into base_frame.
[ INFO] [1573075087.085216969]: lookupTransform base_footprint to laser timed out. Could not transform laser scan into base_frame.
[ INFO] [1573075087.588245462]: lookupTransform base_footprint to laser timed out. Could not transform laser scan into base_frame.
[ INFO] [1573075088.091082835]: lookupTransform base_footprint to laser timed out. Could not transform laser scan into base_frame.
[ INFO] [1573075088.594114949]: lookupTransform base_footprint to laser timed out. Could not transform laser scan into base_frame.
[ WARN] [1573075088.952067557]: /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=10).
/rtabmap/rtabmap subscribed to (approx sync):
   /rtabmap/rgbd_image,
   /scan
[ INFO] [1573075089.096988050]: lookupTransform base_footprint to laser timed out. Could not transform laser scan into base_frame.
[ INFO] [1573075089.600014753]: lookupTransform base_footprint to laser timed out. Could not transform laser scan into base_frame.
[ INFO] [1573075090.102954919]: lookupTransform base_footprint to laser timed out. Could not transform laser scan into base_frame.
and my RVIZ are publishing warnings about TF. RVIZ screen Thank you for you and your incredible team. best regards
Reply | Threaded
Open this post in threaded view
|

Re: mapping with kinect v2 + laser scan

matlabbe
Administrator
Hi,

You must create a TF tree for your setup. You can read this: http://wiki.ros.org/navigation/Tutorials/RobotSetup/TF. You cannot do hand-held mapping with a kinect + 2d lidar in that configuration. In this example, we assumed that we are on a 2D robot.

Explicitly your error is that you don't have TF between the base_foorprint frame of the robot and the laser frame. Without going through an URDF and robot_state_publisher, you can simply add manually the missing static transforms with:
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser" 
    args="0.0 0.0 0.3 0.0 0.0 0.0 /base_footprint /laser 100" />
Here assuming the lidar is 30 cm over the base_footprint. You may have to do the same for the camera.

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

Re: mapping with kinect v2 + laser scan

ricardo
This post was updated on .
Hi Mathieu, I was not precise when I said that that I trying to do a handheld mapping with Laser+Kinect. In my lab we bough a 2d robot however we have to wait until it arrives. I`m a beginner in ROS and I would like to know if is possible to use RTABMap with laser and Kinect without a robot. If yes, which static transform do I have to set to get the laser and Kinect working in a fake 2d robot (wood structure with wheels)? thak you
====EDIT======
Today latter, after digging and read some posts I could finaly get some good results. First, I edit my lanch file and add some static transforms.
  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
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
<launch>
 
  <!-- Choose visualization -->
  <arg name="rviz" default="false" />
  <arg name="rtabmapviz" default="true" />
  
  <!-- Choose hector_slam or icp_odometry for odometry -->
  <arg name="hector" default="true" />

  <param name="use_sim_time" type="bool" value="false"/>
  
  <node if="$(arg hector)" pkg="tf" type="static_transform_publisher" name="scanmatcher_to_base_footprint" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /scanmatcher_frame /base_footprint 100" />
  
 <node pkg="tf" type="static_transform_publisher" name="laser_2_base_link" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /base_footprint /laser 100" />

  <node pkg="tf" type="static_transform_publisher" name="kinect2_2_base_link" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /base_footprint /kinect2_link 100" />

  <!-- Odometry from laser scans -->
  <!-- If argument "hector" is true, we use Hector mapping to generate odometry for us -->
  <node if="$(arg hector)" pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
    
    <!-- Frame names -->
    <param name="map_frame" value="hector_map" />
    <param name="base_frame" value="base_footprint" />
    <param name="odom_frame" value="odom" />
    
    <!-- Tf use -->
    <param name="pub_map_odom_transform" value="false"/>
    <param name="pub_map_scanmatch_transform" value="true"/>
    <param name="pub_odometry" value="true"/>
    
    <!-- Map size / start point -->
    <param name="map_resolution" value="0.025"/>
    <param name="map_size" value="2048"/>
    <param name="map_multi_res_levels" value="2" />
    
    <!-- Map update parameters -->
    <param name="map_update_angle_thresh" value="0.06" />
    
    <!-- Advertising config --> 
    <param name="scan_topic" value="/scan"/>
  </node>
  
  <!-- If argument "hector" is false, we use rtabmap's icp odometry to generate odometry for us -->
  <node unless="$(arg hector)" pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="screen" >
     <remap from="scan"      to="/scan"/>
     <remap from="odom"      to="/scanmatch_odom"/>
     <remap from="odom_info"      to="/rtabmap/odom_info"/>
	  
     <param name="frame_id"        type="string" value="base_footprint"/>   
     
     <param name="Icp/PointToPlane"  type="string" value="true"/>
     <param name="Icp/VoxelSize"     type="string" value="0.05"/>
     <param name="Icp/Epsilon"       type="string" value="0.001"/>
     <param name="Icp/PointToPlaneK"  type="string" value="5"/>
     <param name="Icp/PointToPlaneRadius"  type="string" value="0.3"/>
     <param name="Icp/MaxCorrespondenceDistance" type="string" value="0.1"/>
     <param name="Icp/PM"             type="string" value="true"/> <!-- use libpointmatcher to handle PointToPlane with 2d scans-->
     <param name="Icp/PMOutlierRatio" type="string" value="0.95"/>
     <param name="Odom/Strategy"        type="string" value="0"/>
     <param name="Odom/GuessMotion"     type="string" value="true"/>
     <param name="Odom/ResetCountdown"  type="string" value="0"/>
     <param name="Odom/ScanKeyFrameThr"  type="string" value="0.9"/>
  </node>

  <group ns="rtabmap">
    <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="screen">
      <remap from="rgb/image"       to="/kinect2/hd/image_color_rect"/>
      <remap from="depth/image"     to="/kinect2/hd/image_depth_rect"/>
      <remap from="rgb/camera_info" to="/kinect2/hd/camera_info"/>
      <!--
      <param name="rgb/image_transport"   type="string" value="compressed"/>
      <param name="depth/image_transport" type="string" value="compressedDepth"/>
      -->
    </node>

    <!-- SLAM -->
    <!-- args: "delete_db_on_start" and "udebug" -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
      <param name="frame_id" type="string" value="base_footprint"/>
	
      <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="scan" to="/scan"/>

      <!-- As hector doesn't provide compatible covariance in the odometry topic, don't use the topic and fix the covariance -->
      <param if="$(arg hector)" name="odom_frame_id"            type="string" value="hector_map"/>
      <param if="$(arg hector)" name="odom_tf_linear_variance"  type="double" value="0.0005"/>
      <param if="$(arg hector)" name="odom_tf_angular_variance" type="double" value="0.0005"/>

      <remap unless="$(arg hector)" from="odom" to="/scanmatch_odom"/>
      <param unless="$(arg hector)" name="subscribe_odom_info" type="bool" value="true"/>
	
      <!-- RTAB-Map's parameters -->
      <param name="Reg/Strategy"       type="string" value="0"/>    <!-- 0=Visual, 1=ICP, 2=Visual+ICP -->
      <param name="Reg/Force3DoF"      type="string" value="true"/>
      <param name="RGBD/ProximityBySpace"      type="string" value="false"/>
    </node>
    
    <!-- Visualisation RTAB-Map -->
    <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
      <param name="subscribe_rgbd"      type="bool" value="true"/>
      <param name="subscribe_laserScan" type="bool" value="true"/>
      <param name="frame_id"            type="string" value="base_footprint"/>
    
      <remap from="scan"            to="/scan"/>

      <!-- As hector doesn't provide compatible covariance in the odometry topic -->
      <param if="$(arg hector)" name="odom_frame_id" type="string" value="hector_map"/>

      <remap unless="$(arg hector)" from="odom" to="/scanmatch_odom"/>
      <param unless="$(arg hector)" name="subscribe_odom_info" type="bool" value="true"/>
    </node>
  
  </group>
  
  <!-- Visualisation RVIZ -->
  <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(find rtabmap_ros)/launch/config/demo_robot_mapping.rviz" output="screen"/>
   <node pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb">
    <remap from="rgbd_image"      to="/rtabmap/rgbd_image"/>
    <remap from="cloud"           to="voxel_cloud" />

    <param name="voxel_size" type="double" value="0.01"/>
  </node>

</launch>
and then launch on my terminal
$ roscore
$ roslaunch urg_node urg_lidar.launch
$ roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true
$ roslaunch my_rtabmap demo_rtabmap.launch 
Now I abble to see the mapping mode and the clouds, the tf tree, and the rqt as following
TF TREE
However, when I`m in the mapping process, my 3d point cloud somehow looks to be disorganized as presented in the image below.
Mapping Process
point cloud downloaded
Do you have any suggestions about how to get the cloud organized as it keeps in handheld mapping? Thank you
Reply | Threaded
Open this post in threaded view
|

Re: mapping with kinect v2 + laser scan

matlabbe
Administrator
Hi,

What is the frame_id in the header of rgb/depth images? If it is /kinect2_link, you may want to put an optical transformation in this transform:
<node pkg="tf" type="static_transform_publisher" name="kinect2_2_base_link" 
    args="0.0 0.0 0.0 -1.5707963267948966 0.0 -1.5707963267948966 /base_footprint /kinect2_link 100" />

cheers,
Mathieu