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();
Comment thread
SteveMacenski marked this conversation as resolved.

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
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think you need either the object or the method, its already provided for you since you derive from the costmap layer class which has a costmap2D in the inheritance tree https://github.com/ros-planning/navigation2/blob/aaa97902c1e1bb9a509c4ee0d88b880afb528f20/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp#L314

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I thought so first, but actually InflationLayer is not Costmap2D but just a Layer.
The other three layers (Obstacle, Voxel, Static) are derived from CostmapLayer which derived from Layer and Costmap2D. I also considered moving the mutex things from Costmap2D to Layer but they are used in LayeredCostmap which just uses Costmap2D as a private member.

So I needed to redefine them.
One possible alternative is having mutex things in LayeredCosmap and Layer for future additional plugins.
What do you think?

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Huh got it, thanks. @AlexeyMerzlyakov maybe the costmap filter base class should just be a layer and not a costmap layer, then you won't have that pesky costmap_ internally https://github.com/ros-planning/navigation2/pull/1882/files. I think where we left it is we'd have a mask_costmap_ or similar so we could just get rid of that in general.

Thanks for that note, I hadn't recognized that subtly.

Copy link
Copy Markdown
Collaborator

@AlexeyMerzlyakov AlexeyMerzlyakov Aug 17, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe the costmap filter base class should just be a layer and not a costmap layer

Good point to have in CostmapFilter class from #1882 in order to avoid costmap_ resource potential mishandle in the future. I've added locally similar access_ into that class and changed inheritance and it looks to work fine.

BTW, from first sight it looks like CostmapLayer class is not locking its resources when making any work with them (e.g. during the updateWithMax(), updateWithOverwrite(), etc... routines). Why do not add working with the access lock into CostmapLayer as well?

Finally, this PR was merged, but I can not find any commit in the master/main branch related to. Am I wrong, or is it some merge problem?

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You don't need the locking in update functions for costmap filters necessarily. Inflation needs it because it has an async callback function editing a cache table that is also used by update (that could be called at the same time). I think how we've designed the costmap filters layer, there's no chance for that because we don't even allow it to update anything until after we've received something over the topic and set the variable. We should though look over it again and verify that is true. The update with XYZ doesn't need a lock because we're updating the master_grid which is only edited by the plugins, in a single threaded order. The locks are to protect the local costmap_ isntances that can be edited by multiple things if there are callback functions being processed in the active state (like inflation, static, voxel, obstacles)

Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, I've got your point. This indeed will be excessive.
However, I still have some doubts about CostmapLayer class: if compare it with Costmap2D class (from which it was inherited), we can see that there some work with costmap_ methods are being protected by a mutex (e.g. Costmap2D::resetMaps() or Costmap2D::resizeMap()). However, I can not see any callbacks inside Costmap2D; it looks like a costmap_ is being protected for async calls of above API methods from outside. Maybe there is some other intention why the mutex is added in Costmap2D only, I can not get it yet, but for now it seems little bit unclear.

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());
Comment thread
SteveMacenski marked this conversation as resolved.
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