Skip to content

Commit

Permalink
Mutex updateMap, as it gets also called from MBF service (#103)
Browse files Browse the repository at this point in the history
  • Loading branch information
corot authored Nov 12, 2024
1 parent dca95ff commit 9d3856d
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
2 changes: 1 addition & 1 deletion costmap_2d/include/costmap_2d/costmap_2d_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -277,7 +277,7 @@ class Costmap2DROS
Costmap2DPublisher* publisher_;
dynamic_reconfigure::Server<costmap_2d::Costmap2DConfig> *dsrv_;

boost::recursive_mutex configuration_mutex_;
boost::recursive_mutex update_mutex_;

ros::Subscriber footprint_sub_;
ros::Publisher footprint_pub_;
Expand Down
6 changes: 3 additions & 3 deletions costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -411,9 +411,6 @@ void Costmap2DROS::setUnpaddedRobotFootprint(const std::vector<geometry_msgs::Po

void Costmap2DROS::movementCB(const ros::TimerEvent &event)
{
// don't allow configuration to happen while this check occurs
// boost::recursive_mutex::scoped_lock mcl(configuration_mutex_);

geometry_msgs::PoseStamped new_pose;

if (!getRobotPose(new_pose))
Expand Down Expand Up @@ -482,6 +479,9 @@ void Costmap2DROS::mapUpdateLoop(double frequency)

void Costmap2DROS::updateMap()
{
// allow parallel calls, in case user wants to update without waiting for the update loop
boost::recursive_mutex::scoped_lock lock(update_mutex_);

if (!stop_updates_)
{
// get global pose
Expand Down

0 comments on commit 9d3856d

Please sign in to comment.