Skip to content

Commit

Permalink
Reduce mutex scope in publishTransformLoop
Browse files Browse the repository at this point in the history
  • Loading branch information
jsongCMU committed Dec 22, 2022
1 parent a358c6d commit ebee42b
Showing 1 changed file with 8 additions and 3 deletions.
11 changes: 8 additions & 3 deletions slam_toolbox/src/slam_toolbox_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,10 +206,15 @@ void SlamToolbox::publishTransformLoop(const double& transform_publish_period)
while(ros::ok())
{
{
// Create copy of map-to-odom TFs map
std::map<std::string, tf2::Transform> local_TFs_map;
{
boost::mutex::scoped_lock lock(map_to_odom_mutex_);
local_TFs_map = m_map_to_odoms_;
}
// Publish all past and current transforms so none of them go stale
boost::mutex::scoped_lock lock(map_to_odom_mutex_);
std::map<std::string, tf2::Transform>::iterator iter;
for(iter = m_map_to_odoms_.begin(); iter != m_map_to_odoms_.end(); iter++)
std::map<std::string, tf2::Transform>::const_iterator iter;
for(iter = local_TFs_map.begin(); iter != local_TFs_map.end(); iter++)
{
geometry_msgs::TransformStamped msg;
tf2::convert(iter->second, msg.transform);
Expand Down

0 comments on commit ebee42b

Please sign in to comment.