@@ -325,15 +325,18 @@ VoxelGridDynamicMapLoader::VoxelGridDynamicMapLoader(
325
325
}
326
326
void VoxelGridDynamicMapLoader::onEstimatedPoseCallback (nav_msgs::msg::Odometry::ConstSharedPtr msg)
327
327
{
328
+ std::lock_guard<std::mutex> lock (dynamic_map_loader_mutex_);
328
329
current_position_ = msg->pose .pose .position ;
329
330
}
330
331
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)
332
335
{
333
336
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_);
337
340
if (
338
341
static_cast <size_t >(neighbor_map_grid_index) >= current_voxel_grid_array_.size () ||
339
342
neighbor_map_grid_index == current_map_grid_index ||
@@ -352,7 +355,10 @@ bool VoxelGridDynamicMapLoader::is_close_to_next_map_grid(
352
355
bool VoxelGridDynamicMapLoader::is_close_to_map (
353
356
const pcl::PointXYZ & point, const double distance_threshold)
354
357
{
358
+ // std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
359
+ dynamic_map_loader_mutex_.lock ();
355
360
if (current_voxel_grid_dict_.size () == 0 ) {
361
+ dynamic_map_loader_mutex_.unlock ();
356
362
return false ;
357
363
}
358
364
@@ -363,66 +369,75 @@ bool VoxelGridDynamicMapLoader::is_close_to_map(
363
369
map_grids_x_ * std::floor ((point.y - origin_y_) / map_grid_size_y_));
364
370
365
371
if (static_cast <size_t >(map_grid_index) >= current_voxel_grid_array_.size ()) {
372
+ dynamic_map_loader_mutex_.unlock ();
366
373
return false ;
367
374
}
368
375
if (
369
376
current_voxel_grid_array_.at (map_grid_index) != nullptr &&
370
377
is_close_to_neighbor_voxels (
371
378
point, distance_threshold, current_voxel_grid_array_.at (map_grid_index)->map_cell_pc_ptr ,
372
379
current_voxel_grid_array_.at (map_grid_index)->map_cell_voxel_grid )) {
380
+ dynamic_map_loader_mutex_.unlock ();
373
381
return true ;
374
382
}
375
383
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
+
376
391
// Compare point with the neighbor map cells if point close to map cell boundary
377
392
378
393
if (is_close_to_next_map_grid (
379
394
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 )) {
381
396
return true ;
382
397
}
383
398
384
399
if (is_close_to_next_map_grid (
385
400
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 )) {
387
402
return true ;
388
403
}
389
404
390
405
if (is_close_to_next_map_grid (
391
406
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 )) {
393
408
return true ;
394
409
}
395
410
if (is_close_to_next_map_grid (
396
411
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 )) {
398
413
return true ;
399
414
}
400
415
401
416
return false ;
402
417
}
403
418
void VoxelGridDynamicMapLoader::timer_callback ()
404
419
{
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) {
411
425
return ;
412
426
}
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 ()) ;
418
432
}
433
+ last_updated_position_ = current_position;
419
434
}
420
435
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
422
439
{
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) {
426
441
return true ;
427
442
}
428
443
return false ;
0 commit comments