Skip to content

Commit 52c5459

Browse files
committed
fix: change to lock_guard
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 9d844df commit 52c5459

File tree

5 files changed

+50
-49
lines changed

5 files changed

+50
-49
lines changed

Diff for: perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@ bool DistanceBasedStaticMapLoader::is_close_to_map(
7676
bool DistanceBasedDynamicMapLoader::is_close_to_map(
7777
const pcl::PointXYZ & point, const double distance_threshold)
7878
{
79+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
7980
if (current_voxel_grid_dict_.size() == 0) {
8081
return false;
8182
}

Diff for: perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@ 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+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
4849
if (current_voxel_grid_dict_.size() == 0) {
4950
return false;
5051
}

Diff for: perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -80,6 +80,7 @@ bool VoxelDistanceBasedStaticMapLoader::is_close_to_map(
8080
bool VoxelDistanceBasedDynamicMapLoader::is_close_to_map(
8181
const pcl::PointXYZ & point, const double distance_threshold)
8282
{
83+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
8384
if (current_voxel_grid_dict_.size() == 0) {
8485
return false;
8586
}

Diff for: perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp

+33-34
Original file line numberDiff line numberDiff line change
@@ -355,39 +355,36 @@ bool VoxelGridDynamicMapLoader::is_close_to_next_map_grid(
355355
bool VoxelGridDynamicMapLoader::is_close_to_map(
356356
const pcl::PointXYZ & point, const double distance_threshold)
357357
{
358-
// std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
359-
dynamic_map_loader_mutex_.lock();
360-
if (current_voxel_grid_dict_.size() == 0) {
361-
dynamic_map_loader_mutex_.unlock();
362-
return false;
363-
}
364-
365-
// Compare point with map grid that point belong to
366-
367-
int map_grid_index = static_cast<int>(
368-
std::floor((point.x - origin_x_) / map_grid_size_x_) +
369-
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));
370-
371-
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
372-
dynamic_map_loader_mutex_.unlock();
373-
return false;
374-
}
375-
if (
376-
current_voxel_grid_array_.at(map_grid_index) != nullptr &&
377-
is_close_to_neighbor_voxels(
378-
point, distance_threshold, current_voxel_grid_array_.at(map_grid_index)->map_cell_pc_ptr,
379-
current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid)) {
380-
dynamic_map_loader_mutex_.unlock();
381-
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+
}
382386
}
383387

384-
auto origin_x = origin_x_;
385-
auto origin_y = origin_y_;
386-
auto map_grid_size_x = map_grid_size_x_;
387-
auto map_grid_size_y = map_grid_size_y_;
388-
auto map_grids_x = map_grids_x_;
389-
dynamic_map_loader_mutex_.unlock();
390-
391388
// Compare point with the neighbor map cells if point close to map cell boundary
392389

393390
if (is_close_to_next_map_grid(
@@ -417,9 +414,11 @@ bool VoxelGridDynamicMapLoader::is_close_to_map(
417414
}
418415
void VoxelGridDynamicMapLoader::timer_callback()
419416
{
420-
dynamic_map_loader_mutex_.lock();
421-
auto current_position = current_position_;
422-
dynamic_map_loader_mutex_.unlock();
417+
std::optional<geometry_msgs::msg::Point> current_position = std::nullopt;
418+
{
419+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
420+
current_position = current_position_;
421+
}
423422

424423
if (current_position == std::nullopt) {
425424
return;

Diff for: perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp

+14-15
Original file line numberDiff line numberDiff line change
@@ -279,22 +279,21 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
279279
virtual inline void addMapCellAndFilter(
280280
const autoware_map_msgs::msg::PointCloudMapCellWithID & map_cell_to_add)
281281
{
282-
dynamic_map_loader_mutex_.lock();
283-
map_grid_size_x_ = map_cell_to_add.metadata.max_x - map_cell_to_add.metadata.min_x;
284-
map_grid_size_y_ = map_cell_to_add.metadata.max_y - map_cell_to_add.metadata.min_y;
285-
if (map_grid_size_x_ > max_map_grid_size_ || map_grid_size_y_ > max_map_grid_size_) {
286-
dynamic_map_loader_mutex_.unlock();
287-
RCLCPP_ERROR(
288-
logger_,
289-
"Map was not split or split map grid size is too large. Split map with grid size smaller "
290-
"than %f",
291-
max_map_grid_size_);
292-
}
293-
294-
origin_x_remainder_ = std::remainder(map_cell_to_add.metadata.min_x, map_grid_size_x_);
295-
origin_y_remainder_ = std::remainder(map_cell_to_add.metadata.min_y, map_grid_size_y_);
296-
dynamic_map_loader_mutex_.unlock();
282+
{
283+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
284+
map_grid_size_x_ = map_cell_to_add.metadata.max_x - map_cell_to_add.metadata.min_x;
285+
map_grid_size_y_ = map_cell_to_add.metadata.max_y - map_cell_to_add.metadata.min_y;
286+
if (map_grid_size_x_ > max_map_grid_size_ || map_grid_size_y_ > max_map_grid_size_) {
287+
RCLCPP_ERROR(
288+
logger_,
289+
"Map was not split or split map grid size is too large. Split map with grid size smaller "
290+
"than %f",
291+
max_map_grid_size_);
292+
}
297293

294+
origin_x_remainder_ = std::remainder(map_cell_to_add.metadata.min_x, map_grid_size_x_);
295+
origin_y_remainder_ = std::remainder(map_cell_to_add.metadata.min_y, map_grid_size_y_);
296+
}
298297
pcl::PointCloud<pcl::PointXYZ> map_cell_pc_tmp;
299298
pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp);
300299

0 commit comments

Comments
 (0)