Skip to content

Commit

Permalink
Reference Issue #592 Added warning to AMCL when map is published on .…
Browse files Browse the repository at this point in the history
….. (#604)
  • Loading branch information
vik748 authored and mikeferguson committed Aug 2, 2017
1 parent bbe39f0 commit d2fd4f3
Showing 1 changed file with 5 additions and 0 deletions.
5 changes: 5 additions & 0 deletions amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -802,6 +802,11 @@ AmclNode::handleMapMessage(const nav_msgs::OccupancyGrid& msg)
msg.info.width,
msg.info.height,
msg.info.resolution);

if(msg.header.frame_id != global_frame_id_)
ROS_WARN("Frame_id of map received:'%s' doesn't match global_frame_id:'%s;'. This could cause issues with reading published topics",
msg.header.frame_id.c_str(),
global_frame_id_.c_str());

freeMapDependentMemory();
// Clear queued laser objects because they hold pointers to the existing
Expand Down

0 comments on commit d2fd4f3

Please sign in to comment.