In mapping mode, there are some events that can trigger a map update:
- Pose correction with the laser scans (if "RGBD/PoseScanMatching"="true")
- Loop closure detection
- Transfer/Retrieval of nodes (if "Rtabmap/TimeThr" > "0")
- If "RGBD/OptimizeFromGraphEnd" = "true", the whole map is always optimized from the last pose instead of the first pose in the map. You can try to enable/disable it to see what happens. Well, if you set to false, the map will be "nailed down" on the first node of the map.
Are you talking about the global or the local costmap? The global costmap is generated from the occupancy grid map generated by rtabmap, so they must be always aligned. Here is my
global_costmap_params.yaml for example from the
az3_mapping_robot_nav.launch :
global_frame: map
robot_base_frame: base_footprint
update_frequency: 1
publish_frequency: 2
always_send_full_costmap: false
plugins:
- {name: static_layer, type: "rtabmap_ros::StaticLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
and the related move_base configuration (/map is the generated /grid_map from rtabmap):
<group ns="planner">
<remap from="map" to="/map"/>
<node pkg="move_base" type="move_base" respawn="true" name="move_base" output="screen">
<param name="base_global_planner" value="navfn/NavfnROS"/>
<rosparam file="$(find rtabmap_ros)/launch/azimut3/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find rtabmap_ros)/launch/azimut3/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find rtabmap_ros)/launch/azimut3/config/local_costmap_params_2d.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find rtabmap_ros)/launch/azimut3/config/global_costmap_params.yaml" command="load" ns="global_costmap"/>
<rosparam file="$(find rtabmap_ros)/launch/azimut3/config/base_local_planner_params.yaml" command="load" />
</node>
</group>
If you have a screenshot of the problem and a launch file example (rtabmap and move_base stuff), it may help to understand better if you have still problems.
Cheers,
Mathieu