I know it's possible to do 2D SLAM with Kinect using slam_gmapping, eg. because of this post. Could anyone please tell me how exactly to do that?
I've already installed pointcloud_to_laserscan, slam_gmapping, turtlebot and turtlebot_apps. But after running roslaunch turtlebot_navigation gmapping_demo.launch all I'm getting is an info saying: "Still waiting on map". What and in which order should I execute to obtain a map like in turtlebot_navigation's tutorial?
Ok, I think I partially got it. There were some errors in the default pointcloud_to_laserscan launchfile. My working version below.
<launch>
<!-- kinect and frame ids -->
<include file="$(find openni_camera)/launch/openni_node.launch"/>
<!-- Kinect -->
<node pkg="nodelet" type="nodelet" name="openni_manager" output="screen" respawn="true" args="manager"/>
<!-- fake laser -->
<node pkg="nodelet" type="nodelet" name="kinect_laser" args="load pointcloud_to_laserscan/CloudToScan openni_camera">
<param name="output_frame_id" value="/openni_depth_frame"/>
<remap from="cloud" to="cloud_throttled"/>
</node>
<!-- throttling -->
<node pkg="nodelet" type="nodelet" name="pointcloud_throttle" args="load pointcloud_to_laserscan/CloudThrottle openni_camera">
<param name="max_rate" value="2"/>
<remap from="cloud_in" to="/camera/depth/points"/>
<remap from="cloud_out" to="cloud_throttled"/>
</node>
</launch>
When I now run rosrun gmapping slam_gmapping I get a warning saying:
[ WARN] [1300374330.893690231]: MessageFilter [target=/odom ]: Dropped 100.00% of messages so far. Please turn the [ros.gmapping.message_notifier] rosconsole logger to DEBUG for more information.
[DEBUG] [1300374332.317853661]: MessageFilter [target=/odom ]: Removed oldest message because buffer is full, count now 5 (frame_id=/kinect_depth_frame, stamp=1300374331.992896)
[DEBUG] [1300374332.318014019]: MessageFilter [target=/odom ]: Added message in frame /kinect_depth_frame at time 1300374332.311, count now 5
[DEBUG] [1300374332.376768593]: MessageFilter [target=/odom ]: Removed oldest message because buffer is full, count now 5 (frame_id=/kinect_depth_frame, stamp=1300374332.060879)
I think the problem might be there is no tf tree between /openni_camera and /map defined - how do I achieve this?
Any help appreciated, Tom.
Hi Tom,
This does not answer your gmapping question, but the launch file you posted above does not work for me. It runs without error but it does not produce a "/scan" topic for the fake laser scan. In other words, run your launch file, then in a separate terminal run the command "rostopic list | grep scan". It should return "/scan" but in my case it returns nothing.
The following modified version of your launch file does work for me:
<launch>
<!-- kinect and frame ids -->
<include file="$(find openni_camera)/launch/openni_node.launch"/>
<!-- openni manager -->
<node pkg="nodelet" type="nodelet" name="openni_manager" output="screen" respawn="true" args="manager"/>
<!-- throttling -->
<node pkg="nodelet" type="nodelet" name="pointcloud_throttle" args="load pointcloud_to_laserscan/CloudThrottle openni_manager">
<param name="max_rate" value="2"/>
<remap from="cloud_in" to="/camera/depth/points"/>
<remap from="cloud_out" to="cloud_throttled"/>
</node>
<!-- fake laser -->
<node pkg="nodelet" type="nodelet" name="kinect_laser" args="load pointcloud_to_laserscan/CloudToScan openni_manager">
<param name="output_frame_id" value="/openni_depth_frame"/>
<remap from="cloud" to="cloud_throttled"/>
</node>
</launch>
The important difference is that the two nodelets now wait on openni_manager rather than openni_camera.
Using this launch file, I can add a Laser Scan display in RViz and select the "scan" topic and see the scan points.
Regarding your gmapping question, you don't mention what kind of robot you are using. Is it an iRobot Create? If so, are you using an IMU with it? Also, have you run through all the Navigation tutorials starting here: http://www.ros.org/wiki/navigation/Tutorials?
--patrick
Asked: 2011-03-16 09:29:45 -0500
Seen: 1,689 times
Last updated: Jul 14 '12
How to change fake laser scan direction of rotation
Gmapping doesn't build a clear map
Kinect content missing on the Turtlebot
2D SLAM combine pointcloud_to_laserscan and laser_scan_matcher and gmapping
SLAM without odometry: gmapping or hector_slam?
Corrected Odometry from GMapping / Karto?
ROS Answers is licensed under Creative Commons Attribution 3.0 Content on this site is licensed under a Creative Commons Attribution Share Alike 3.0 license.