ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Thanks to @MicaelKorn I could get the RGBDSLAM work on the Kinect v2. Just to summarize:
rgbdslam_kinect2.launch
with contents like below.roslaunch rgbdslam rgbdslam_kinect2.launch
and rosrun kinect2_bridge kinect2_bridge.launch
from different Terminal windowsNow the RGBDSLAM GUI should appear and does its work.
rgbdslam_kinect2.launch:
<launch>
<node pkg="rgbdslam" type="rgbdslam" name="rgbdslam" cwd="node" required="true" output="screen">
<param name="config/topic_image_depth" value="/kinect2/qhd/image_depth_rect"/>
<param name="config/topic_points" value=""/> <!--if empty, poincloud will be reconstructed from image and depth -->
<!-- These are the default values of some important parameters -->
<param name="config/feature_extractor_type" value="SIFTGPU"/><!-- also available: SIFT, SIFTGPU, SURF, SURF128 (extended SURF), ORB. -->
<param name="config/feature_detector_type" value="SIFTGPU"/><!-- also available: SIFT, SURF, GFTT (good features to track), ORB. -->
<param name="config/detector_grid_resolution" value="3"/><!-- detect on a 3x3 grid (to spread ORB keypoints and parallelize SIFT and SURF) -->
<param name="config/optimizer_skip_step" value="15"/><!-- optimize only every n-th frame -->
<param name="config/cloud_creation_skip_step" value="2"/><!-- subsample the images' pixels (in both, width and height), when creating the cloud (and therefore reduce memory consumption) -->
<param name="config/backend_solver" value="csparse"/><!-- pcg is faster and good for continuous online optimization, cholmod and csparse are better for offline optimization (without good initial guess)-->
<param name="config/pose_relative_to" value="first"/><!-- optimize only a subset of the graph: "largest_loop" = Everything from the earliest matched frame to the current one. Use "first" to optimize the full graph, "inaffected" to optimize only the frames that were matched (not those inbetween for loops) -->
<param name="config/maximum_depth" value="2"/>
<param name="config/subscriber_queue_size" value="20"/>
<param name="config/min_sampled_candidates" value="30"/><!-- Frame-to-frame comparisons to random frames (big loop closures) -->
<param name="config/predecessor_candidates" value="20"/><!-- Frame-to-frame comparisons to sequential frames-->
<param name="config/neighbor_candidates" value="20"/><!-- Frame-to-frame comparisons to graph neighbor frames-->
<param name="config/ransac_iterations" value="140"/>
<param name="config/g2o_transformation_refinement" value="1"/>
<param name="config/icp_method" value="gicp"/> <!-- icp, gicp ... -->
<!--
<param name="config/max_rotation_degree" value="20"/>
<param name="config/max_translation_meter" value="0.5"/>
<param name="config/min_matches" value="30"/>
<param name="config/min_translation_meter" value="0.05"/>
<param name="config/min_rotation_degree" value="3"/>
<param name="config/g2o_transformation_refinement" value="2"/>
<param name="config/min_rotation_degree" value="10"/>
<param name="config/matcher_type" value="SIFTGPU"/>
-->
</node>
</launch>