Skip to content

Commit 9d844df

Browse files
committed
fix(compare_map_filter): deadlock bug fix
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 9d61ff1 commit 9d844df

File tree

2 files changed

+48
-26
lines changed

2 files changed

+48
-26
lines changed

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp

+38-23
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,7 +355,10 @@ 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
{
358+
// std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
359+
dynamic_map_loader_mutex_.lock();
355360
if (current_voxel_grid_dict_.size() == 0) {
361+
dynamic_map_loader_mutex_.unlock();
356362
return false;
357363
}
358364

@@ -363,66 +369,75 @@ bool VoxelGridDynamicMapLoader::is_close_to_map(
363369
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));
364370

365371
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
372+
dynamic_map_loader_mutex_.unlock();
366373
return false;
367374
}
368375
if (
369376
current_voxel_grid_array_.at(map_grid_index) != nullptr &&
370377
is_close_to_neighbor_voxels(
371378
point, distance_threshold, current_voxel_grid_array_.at(map_grid_index)->map_cell_pc_ptr,
372379
current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid)) {
380+
dynamic_map_loader_mutex_.unlock();
373381
return true;
374382
}
375383

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+
376391
// Compare point with the neighbor map cells if point close to map cell boundary
377392

378393
if (is_close_to_next_map_grid(
379394
pcl::PointXYZ(point.x - distance_threshold, point.y, point.z), map_grid_index,
380-
distance_threshold)) {
395+
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
381396
return true;
382397
}
383398

384399
if (is_close_to_next_map_grid(
385400
pcl::PointXYZ(point.x + distance_threshold, point.y, point.z), map_grid_index,
386-
distance_threshold)) {
401+
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
387402
return true;
388403
}
389404

390405
if (is_close_to_next_map_grid(
391406
pcl::PointXYZ(point.x, point.y - distance_threshold, point.z), map_grid_index,
392-
distance_threshold)) {
407+
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
393408
return true;
394409
}
395410
if (is_close_to_next_map_grid(
396411
pcl::PointXYZ(point.x, point.y + distance_threshold, point.z), map_grid_index,
397-
distance_threshold)) {
412+
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
398413
return true;
399414
}
400415

401416
return false;
402417
}
403418
void VoxelGridDynamicMapLoader::timer_callback()
404419
{
405-
if (current_position_ == std::nullopt) {
406-
return;
407-
}
408-
if (last_updated_position_ == std::nullopt) {
409-
request_update_map(current_position_.value());
410-
last_updated_position_ = current_position_;
420+
dynamic_map_loader_mutex_.lock();
421+
auto current_position = current_position_;
422+
dynamic_map_loader_mutex_.unlock();
423+
424+
if (current_position == std::nullopt) {
411425
return;
412426
}
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_;
427+
if (
428+
last_updated_position_ == std::nullopt ||
429+
should_update_map(
430+
current_position.value(), last_updated_position_.value(), map_update_distance_threshold_)) {
431+
request_update_map(current_position.value());
418432
}
433+
last_updated_position_ = current_position;
419434
}
420435

421-
bool VoxelGridDynamicMapLoader::should_update_map() const
436+
bool VoxelGridDynamicMapLoader::should_update_map(
437+
const geometry_msgs::msg::Point & current_point, const geometry_msgs::msg::Point & last_point,
438+
const double map_update_distance_threshold) const
422439
{
423-
if (
424-
distance2D(current_position_.value(), last_updated_position_.value()) >
425-
map_update_distance_threshold_) {
440+
if (distance2D(current_point, last_point) > map_update_distance_threshold) {
426441
return true;
427442
}
428443
return false;

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp

+10-3
Original file line numberDiff line numberDiff line change
@@ -190,12 +190,16 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
190190
void onEstimatedPoseCallback(nav_msgs::msg::Odometry::ConstSharedPtr msg);
191191

192192
void timer_callback();
193-
bool should_update_map() const;
193+
bool should_update_map(
194+
const geometry_msgs::msg::Point & current_point, const geometry_msgs::msg::Point & last_point,
195+
const double map_update_distance_threshold) const;
194196
void request_update_map(const geometry_msgs::msg::Point & position);
195197
bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) override;
196198
/** \brief Check if point close to map pointcloud in the */
197199
bool is_close_to_next_map_grid(
198-
const pcl::PointXYZ & point, const int current_map_grid_index, const double distance_threshold);
200+
const pcl::PointXYZ & point, const int current_map_grid_index, const double distance_threshold,
201+
const double origin_x, const double origin_y, const double map_grid_size_x,
202+
const double map_grid_size_y, const int map_grids_x);
199203

200204
inline pcl::PointCloud<pcl::PointXYZ> getCurrentDownsampledMapPc()
201205
{
@@ -235,6 +239,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
235239
/** Update loaded map grid array for fast searching*/
236240
virtual inline void updateVoxelGridArray()
237241
{
242+
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
238243
origin_x_ = std::floor((current_position_.value().x - map_loader_radius_) / map_grid_size_x_) *
239244
map_grid_size_x_ +
240245
origin_x_remainder_;
@@ -253,7 +258,6 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
253258

254259
current_voxel_grid_array_.assign(
255260
map_grids_x_ * map_grid_size_y_, std::make_shared<MapGridVoxelInfo>());
256-
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
257261
for (const auto & kv : current_voxel_grid_dict_) {
258262
int index = static_cast<int>(
259263
std::floor((kv.second.min_b_x - origin_x_) / map_grid_size_x_) +
@@ -275,9 +279,11 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
275279
virtual inline void addMapCellAndFilter(
276280
const autoware_map_msgs::msg::PointCloudMapCellWithID & map_cell_to_add)
277281
{
282+
dynamic_map_loader_mutex_.lock();
278283
map_grid_size_x_ = map_cell_to_add.metadata.max_x - map_cell_to_add.metadata.min_x;
279284
map_grid_size_y_ = map_cell_to_add.metadata.max_y - map_cell_to_add.metadata.min_y;
280285
if (map_grid_size_x_ > max_map_grid_size_ || map_grid_size_y_ > max_map_grid_size_) {
286+
dynamic_map_loader_mutex_.unlock();
281287
RCLCPP_ERROR(
282288
logger_,
283289
"Map was not split or split map grid size is too large. Split map with grid size smaller "
@@ -287,6 +293,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
287293

288294
origin_x_remainder_ = std::remainder(map_cell_to_add.metadata.min_x, map_grid_size_x_);
289295
origin_y_remainder_ = std::remainder(map_cell_to_add.metadata.min_y, map_grid_size_y_);
296+
dynamic_map_loader_mutex_.unlock();
290297

291298
pcl::PointCloud<pcl::PointXYZ> map_cell_pc_tmp;
292299
pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp);

0 commit comments

Comments
 (0)