Re: rtabmap with octomap and hector slam

Posted by matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/rtabmap-with-octomap-and-hector-slam-tp696p704.html

rtabmap node is missing the odometry input. If you are using hector_mapping in parallel, you can use it like the Kinect+Laser setup with rtabmap to provide odometry (note the TF parameters):
  <node 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 -->
  <!-- We use Hector mapping to generate odometry for us -->
  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping">
    
    <!-- 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>

Then when you call rgbd_mapping.launch, you can add these parameters too:
visual_odometry:=false odom_topic:=/scanmatch_odom subscribe_scan:=true scan_topic:=/scan 

Regarding your tf tree, you should have /world -> /map -> /scanmatch_odom -> /base_footprint. The transform /world -> /base_footprint should not exist.

cheers