Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 10 additions & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@

#include <map>
#include <vector>
#include <mutex>

#include "rclcpp/rclcpp.hpp"
#include "nav2_costmap_2d/layer.hpp"
Expand Down Expand Up @@ -77,7 +78,7 @@ class InflationLayer : public Layer
public:
InflationLayer();

~InflationLayer() override = default;
~InflationLayer();

void onInitialize() override;
void updateBounds(
Expand Down Expand Up @@ -115,6 +116,13 @@ class InflationLayer : public Layer
return cost;
}

// Provide a typedef to ease future code maintenance
typedef std::recursive_mutex mutex_t;
mutex_t * getMutex()
{
return access_;
}

protected:
void onFootprintChanged() override;

Expand Down Expand Up @@ -184,6 +192,7 @@ class InflationLayer : public Layer

// Indicates that the entire costmap should be reinflated next time around.
bool need_reinflation_;
mutex_t * access_;
};

} // namespace nav2_costmap_2d
Expand Down
8 changes: 8 additions & 0 deletions nav2_costmap_2d/plugins/inflation_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,12 @@ InflationLayer::InflationLayer()
last_max_x_(std::numeric_limits<double>::max()),
last_max_y_(std::numeric_limits<double>::max())
{
access_ = new mutex_t();
}

InflationLayer::~InflationLayer()
{
delete access_;
}

void
Expand Down Expand Up @@ -160,6 +166,7 @@ InflationLayer::updateCosts(
int max_i,
int max_j)
{
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
if (!enabled_ || (cell_inflation_radius_ == 0)) {
return;
}
Expand Down Expand Up @@ -305,6 +312,7 @@ InflationLayer::enqueue(
void
InflationLayer::computeCaches()
{
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
if (cell_inflation_radius_ == 0) {
return;
}
Expand Down