2D SLAM with Kinect One

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

2D SLAM with Kinect One

elgarbe
Hello, I manage to make rtabmap to work on my PC.
Right now I'm running it with:
roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true

and

roslaunch rtabmap_ros rgbd_mapping_kinect2.launch resolution:=qhd

Now I would like to make a 2D SLAM with the kinect. Is it possible to get a 2D map and robot localization like hector SLAM and gmaping? The environment will be indoor.

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

Re: 2D SLAM with Kinect One

matlabbe
Administrator
Hi,

For convenience, we could also just set gen_scan to true in rgbd_mapping_kinect2.launch, then set Reg/Force3DoF to true and Grid/FromDepth to false:
<group ns="rtabmap">
  
    <!-- Odometry -->
    <node pkg="rtabmap_ros" type="rgbd_odometry" name="visual_odometry" output="screen">
      <remap from="rgb/image" to="/kinect2/$(arg resolution)/image_color_rect"/>
      <remap from="depth/image" to="/kinect2/$(arg resolution)/image_depth_rect"/>
      <remap from="rgb/camera_info" to="/kinect2/$(arg resolution)/camera_info"/>

      <param name="frame_id" type="string" value="$(arg frame_id)"/>
      <param name="approx_sync" type="bool" value="false"/>
	  
      <param name="GFTT/BlockSize" type="string" value="$(arg gftt_block_size)"/>
      <param name="GFTT/MinDistance" type="string" value="$(arg gftt_min_distance)"/>
      <param name="Reg/Force3DoF" type="string" value="true"/>                          <!-- HERE -->
    </node>
  
    <!-- Visual SLAM (robot side) -->
    <!-- args: "delete_db_on_start" and "udebug" -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
      <param name="subscribe_depth" type="bool" value="true"/>
      <param name="frame_id" type="string" value="$(arg frame_id)"/>
	
      <remap from="rgb/image" to="/kinect2/$(arg resolution)/image_color_rect"/>
      <remap from="depth/image" to="/kinect2/$(arg resolution)/image_depth_rect"/>
      <remap from="rgb/camera_info" to="/kinect2/$(arg resolution)/camera_info"/>

      <param name="approx_sync" type="bool" value="false"/>
      <param name="gen_scan" type="bool" value="true"/>                                 <!-- HERE -->
      
      <param name="GFTT/BlockSize" type="string" value="$(arg gftt_block_size)"/>
      <param name="GFTT/MinDistance" type="string" value="$(arg gftt_min_distance)"/>
      <param name="Reg/Force3DoF" type="string" value="true"/>                          <!-- HERE -->
      <param name="Grid/FromDepth" type="string" value="false"/>                        <!-- HERE -->
</node>
...
</group>

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

Re: 2D SLAM with Kinect One

elgarbe
Is there any doc from Grid/FromDepth ? I can't find it uses

thank
Reply | Threaded
Open this post in threaded view
|

Re: 2D SLAM with Kinect One

matlabbe
Administrator
You can do:
$ rtabmap --params | grep Grid/FromDepth
Param: Grid/FromDepth = "true"               [Create occupancy grid from depth image(s), otherwise it is created from laser scan.]