Skip to content

Commit a2fe630

Browse files
badai-nguyenTetsuKawa
authored andcommitted
fix(compare_map_filter): deadlock bug fix (autowarefoundation#10222)
* fix(compare_map_filter): deadlock bug fix Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: change to lock_guard Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: CI error Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * reduce scope of mutex Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * refactor Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: refactor Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: add missing mutex for map_grid_size_x Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 2ddea1a commit a2fe630

File tree

7 files changed

+152
-117
lines changed

7 files changed

+152
-117
lines changed

perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp

+24-23
Original file line numberDiff line numberDiff line change
@@ -72,39 +72,40 @@ bool DistanceBasedStaticMapLoader::is_close_to_map(
7272
}
7373
return true;
7474
}
75-
7675
bool DistanceBasedDynamicMapLoader::is_close_to_map(
7776
const pcl::PointXYZ & point, const double distance_threshold)
7877
{
79-
if (current_voxel_grid_dict_.size() == 0) {
80-
return false;
81-
}
82-
if (!isFinite(point)) {
83-
return false;
84-
}
78+
std::shared_ptr<pcl::search::Search<pcl::PointXYZ>> map_cell_kdtree;
79+
{
80+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
81+
if (current_voxel_grid_dict_.size() == 0) {
82+
return false;
83+
}
84+
if (!isFinite(point)) {
85+
return false;
86+
}
8587

86-
const int map_grid_index = static_cast<int>(
87-
std::floor((point.x - origin_x_) / map_grid_size_x_) +
88-
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));
88+
const int map_grid_index = static_cast<int>(
89+
std::floor((point.x - origin_x_) / map_grid_size_x_) +
90+
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));
8991

90-
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
91-
return false;
92-
}
93-
if (current_voxel_grid_array_.at(map_grid_index) != nullptr) {
94-
if (current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree == nullptr) {
92+
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
9593
return false;
9694
}
97-
std::vector<int> nn_indices(1);
98-
std::vector<float> nn_distances(1);
99-
if (!current_voxel_grid_array_.at(map_grid_index)
100-
->map_cell_kdtree->nearestKSearch(point, 1, nn_indices, nn_distances)) {
95+
const auto & current_voxel_grid = current_voxel_grid_array_.at(map_grid_index);
96+
if (current_voxel_grid == nullptr) {
10197
return false;
10298
}
103-
if (nn_distances[0] <= distance_threshold) {
104-
return true;
105-
}
99+
map_cell_kdtree = current_voxel_grid->map_cell_kdtree;
106100
}
107-
return false;
101+
102+
std::vector<int> nn_indices(1);
103+
std::vector<float> nn_distances(1);
104+
if (!map_cell_kdtree->nearestKSearch(point, 1, nn_indices, nn_distances)) {
105+
return false;
106+
}
107+
108+
return nn_distances[0] <= distance_threshold;
108109
}
109110

110111
DistanceBasedCompareMapFilterComponent::DistanceBasedCompareMapFilterComponent(

perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -65,8 +65,11 @@ class DistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader
6565
inline void addMapCellAndFilter(
6666
const autoware_map_msgs::msg::PointCloudMapCellWithID & map_cell_to_add) override
6767
{
68-
map_grid_size_x_ = map_cell_to_add.metadata.max_x - map_cell_to_add.metadata.min_x;
69-
map_grid_size_y_ = map_cell_to_add.metadata.max_y - map_cell_to_add.metadata.min_y;
68+
{
69+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
70+
map_grid_size_x_ = map_cell_to_add.metadata.max_x - map_cell_to_add.metadata.min_x;
71+
map_grid_size_y_ = map_cell_to_add.metadata.max_y - map_cell_to_add.metadata.min_y;
72+
}
7073

7174
pcl::PointCloud<pcl::PointXYZ> map_cell_pc_tmp;
7275
pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp);

perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp

+19-18
Original file line numberDiff line numberDiff line change
@@ -45,29 +45,30 @@ bool VoxelBasedApproximateStaticMapLoader::is_close_to_map(
4545
bool VoxelBasedApproximateDynamicMapLoader::is_close_to_map(
4646
const pcl::PointXYZ & point, [[maybe_unused]] const double distance_threshold)
4747
{
48-
if (current_voxel_grid_dict_.size() == 0) {
49-
return false;
50-
}
48+
VoxelGridPointXYZ map_cell_voxel_grid;
49+
{
50+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
51+
if (current_voxel_grid_dict_.size() == 0) {
52+
return false;
53+
}
5154

52-
const int map_grid_index = static_cast<int>(
53-
std::floor((point.x - origin_x_) / map_grid_size_x_) +
54-
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));
55+
const int map_grid_index = static_cast<int>(
56+
std::floor((point.x - origin_x_) / map_grid_size_x_) +
57+
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));
5558

56-
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
57-
return false;
58-
}
59-
if (current_voxel_grid_array_.at(map_grid_index) != nullptr) {
60-
const int index = current_voxel_grid_array_.at(map_grid_index)
61-
->map_cell_voxel_grid.getCentroidIndexAt(
62-
current_voxel_grid_array_.at(map_grid_index)
63-
->map_cell_voxel_grid.getGridCoordinates(point.x, point.y, point.z));
64-
if (index == -1) {
59+
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
6560
return false;
66-
} else {
67-
return true;
6861
}
62+
const auto & current_voxel_grid = current_voxel_grid_array_.at(map_grid_index);
63+
if (current_voxel_grid == nullptr) {
64+
return false;
65+
}
66+
map_cell_voxel_grid = current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid;
6967
}
70-
return false;
68+
69+
const int index = map_cell_voxel_grid.getCentroidIndexAt(
70+
map_cell_voxel_grid.getGridCoordinates(point.x, point.y, point.z));
71+
return (index != -1);
7172
}
7273

7374
VoxelBasedApproximateCompareMapFilterComponent::VoxelBasedApproximateCompareMapFilterComponent(

perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp

+20-16
Original file line numberDiff line numberDiff line change
@@ -80,25 +80,29 @@ bool VoxelDistanceBasedStaticMapLoader::is_close_to_map(
8080
bool VoxelDistanceBasedDynamicMapLoader::is_close_to_map(
8181
const pcl::PointXYZ & point, const double distance_threshold)
8282
{
83-
if (current_voxel_grid_dict_.size() == 0) {
84-
return false;
85-
}
83+
std::shared_ptr<pcl::search::Search<pcl::PointXYZ>> map_cell_kdtree;
84+
VoxelGridPointXYZ map_cell_voxel_grid;
85+
{
86+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
87+
if (current_voxel_grid_dict_.size() == 0) {
88+
return false;
89+
}
8690

87-
const int map_grid_index = static_cast<int>(
88-
std::floor((point.x - origin_x_) / map_grid_size_x_) +
89-
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));
91+
const int map_grid_index = static_cast<int>(
92+
std::floor((point.x - origin_x_) / map_grid_size_x_) +
93+
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));
9094

91-
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
92-
return false;
93-
}
94-
if (
95-
current_voxel_grid_array_.at(map_grid_index) != nullptr &&
96-
is_close_to_neighbor_voxels(
97-
point, distance_threshold, current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid,
98-
current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree)) {
99-
return true;
95+
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
96+
return false;
97+
}
98+
if (current_voxel_grid_array_.at(map_grid_index) == nullptr) {
99+
return false;
100+
}
101+
map_cell_voxel_grid = current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid;
102+
map_cell_kdtree = current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree;
100103
}
101-
return false;
104+
return is_close_to_neighbor_voxels(
105+
point, distance_threshold, map_cell_voxel_grid, map_cell_kdtree);
102106
}
103107

104108
VoxelDistanceBasedCompareMapFilterComponent::VoxelDistanceBasedCompareMapFilterComponent(

perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -71,8 +71,11 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader
7171
inline void addMapCellAndFilter(
7272
const autoware_map_msgs::msg::PointCloudMapCellWithID & map_cell_to_add) override
7373
{
74-
map_grid_size_x_ = map_cell_to_add.metadata.max_x - map_cell_to_add.metadata.min_x;
75-
map_grid_size_y_ = map_cell_to_add.metadata.max_y - map_cell_to_add.metadata.min_y;
74+
{
75+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
76+
map_grid_size_x_ = map_cell_to_add.metadata.max_x - map_cell_to_add.metadata.min_x;
77+
map_grid_size_y_ = map_cell_to_add.metadata.max_y - map_cell_to_add.metadata.min_y;
78+
}
7679

7780
pcl::PointCloud<pcl::PointXYZ> map_cell_pc_tmp;
7881
pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp);

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp

+55-41
Original file line numberDiff line numberDiff line change
@@ -325,15 +325,18 @@ VoxelGridDynamicMapLoader::VoxelGridDynamicMapLoader(
325325
}
326326
void VoxelGridDynamicMapLoader::onEstimatedPoseCallback(nav_msgs::msg::Odometry::ConstSharedPtr msg)
327327
{
328+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
328329
current_position_ = msg->pose.pose.position;
329330
}
330331
bool VoxelGridDynamicMapLoader::is_close_to_next_map_grid(
331-
const pcl::PointXYZ & point, const int current_map_grid_index, const double distance_threshold)
332+
const pcl::PointXYZ & point, const int current_map_grid_index, const double distance_threshold,
333+
const double origin_x, const double origin_y, const double map_grid_size_x,
334+
const double map_grid_size_y, const int map_grids_x)
332335
{
333336
int neighbor_map_grid_index = static_cast<int>(
334-
std::floor((point.x - origin_x_) / map_grid_size_x_) +
335-
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));
336-
337+
std::floor((point.x - origin_x) / map_grid_size_x) +
338+
map_grids_x * std::floor((point.y - origin_y) / map_grid_size_y));
339+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
337340
if (
338341
static_cast<size_t>(neighbor_map_grid_index) >= current_voxel_grid_array_.size() ||
339342
neighbor_map_grid_index == current_map_grid_index ||
@@ -352,77 +355,88 @@ bool VoxelGridDynamicMapLoader::is_close_to_next_map_grid(
352355
bool VoxelGridDynamicMapLoader::is_close_to_map(
353356
const pcl::PointXYZ & point, const double distance_threshold)
354357
{
355-
if (current_voxel_grid_dict_.size() == 0) {
356-
return false;
357-
}
358-
359-
// Compare point with map grid that point belong to
360-
361-
int map_grid_index = static_cast<int>(
362-
std::floor((point.x - origin_x_) / map_grid_size_x_) +
363-
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));
364-
365-
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
366-
return false;
367-
}
368-
if (
369-
current_voxel_grid_array_.at(map_grid_index) != nullptr &&
370-
is_close_to_neighbor_voxels(
371-
point, distance_threshold, current_voxel_grid_array_.at(map_grid_index)->map_cell_pc_ptr,
372-
current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid)) {
373-
return true;
358+
double origin_x, origin_y, map_grid_size_x, map_grid_size_y;
359+
int map_grids_x, map_grid_index;
360+
{
361+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
362+
if (current_voxel_grid_dict_.size() == 0) {
363+
return false;
364+
}
365+
origin_x = origin_x_;
366+
origin_y = origin_y_;
367+
map_grid_size_x = map_grid_size_x_;
368+
map_grid_size_y = map_grid_size_y_;
369+
map_grids_x = map_grids_x_;
370+
// Compare point with map grid that point belong to
371+
372+
map_grid_index = static_cast<int>(
373+
std::floor((point.x - origin_x) / map_grid_size_x) +
374+
map_grids_x * std::floor((point.y - origin_y) / map_grid_size_y));
375+
376+
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
377+
return false;
378+
}
379+
if (
380+
current_voxel_grid_array_.at(map_grid_index) != nullptr &&
381+
is_close_to_neighbor_voxels(
382+
point, distance_threshold, current_voxel_grid_array_.at(map_grid_index)->map_cell_pc_ptr,
383+
current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid)) {
384+
return true;
385+
}
374386
}
375387

376388
// Compare point with the neighbor map cells if point close to map cell boundary
377389

378390
if (is_close_to_next_map_grid(
379391
pcl::PointXYZ(point.x - distance_threshold, point.y, point.z), map_grid_index,
380-
distance_threshold)) {
392+
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
381393
return true;
382394
}
383395

384396
if (is_close_to_next_map_grid(
385397
pcl::PointXYZ(point.x + distance_threshold, point.y, point.z), map_grid_index,
386-
distance_threshold)) {
398+
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
387399
return true;
388400
}
389401

390402
if (is_close_to_next_map_grid(
391403
pcl::PointXYZ(point.x, point.y - distance_threshold, point.z), map_grid_index,
392-
distance_threshold)) {
404+
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
393405
return true;
394406
}
395407
if (is_close_to_next_map_grid(
396408
pcl::PointXYZ(point.x, point.y + distance_threshold, point.z), map_grid_index,
397-
distance_threshold)) {
409+
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
398410
return true;
399411
}
400412

401413
return false;
402414
}
403415
void VoxelGridDynamicMapLoader::timer_callback()
404416
{
405-
if (current_position_ == std::nullopt) {
406-
return;
417+
std::optional<geometry_msgs::msg::Point> current_position;
418+
{
419+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
420+
current_position = current_position_;
407421
}
408-
if (last_updated_position_ == std::nullopt) {
409-
request_update_map(current_position_.value());
410-
last_updated_position_ = current_position_;
422+
423+
if (current_position == std::nullopt) {
411424
return;
412425
}
413-
414-
if (should_update_map()) {
415-
last_updated_position_ = current_position_;
416-
request_update_map((current_position_.value()));
417-
last_updated_position_ = current_position_;
426+
if (
427+
last_updated_position_ == std::nullopt ||
428+
should_update_map(
429+
current_position.value(), last_updated_position_.value(), map_update_distance_threshold_)) {
430+
request_update_map(current_position.value());
418431
}
432+
last_updated_position_ = current_position;
419433
}
420434

421-
bool VoxelGridDynamicMapLoader::should_update_map() const
435+
bool VoxelGridDynamicMapLoader::should_update_map(
436+
const geometry_msgs::msg::Point & current_point, const geometry_msgs::msg::Point & last_point,
437+
const double map_update_distance_threshold)
422438
{
423-
if (
424-
distance2D(current_position_.value(), last_updated_position_.value()) >
425-
map_update_distance_threshold_) {
439+
if (distance2D(current_point, last_point) > map_update_distance_threshold) {
426440
return true;
427441
}
428442
return false;

0 commit comments

Comments
 (0)