@@ -355,39 +355,36 @@ bool VoxelGridDynamicMapLoader::is_close_to_next_map_grid(
355
355
bool VoxelGridDynamicMapLoader::is_close_to_map (
356
356
const pcl::PointXYZ & point, const double distance_threshold)
357
357
{
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
+ }
382
386
}
383
387
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
-
391
388
// Compare point with the neighbor map cells if point close to map cell boundary
392
389
393
390
if (is_close_to_next_map_grid (
@@ -417,9 +414,11 @@ bool VoxelGridDynamicMapLoader::is_close_to_map(
417
414
}
418
415
void VoxelGridDynamicMapLoader::timer_callback ()
419
416
{
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
+ }
423
422
424
423
if (current_position == std::nullopt) {
425
424
return ;
0 commit comments