@@ -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,77 +355,88 @@ 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
{
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
+ }
374
386
}
375
387
376
388
// Compare point with the neighbor map cells if point close to map cell boundary
377
389
378
390
if (is_close_to_next_map_grid (
379
391
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 )) {
381
393
return true ;
382
394
}
383
395
384
396
if (is_close_to_next_map_grid (
385
397
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 )) {
387
399
return true ;
388
400
}
389
401
390
402
if (is_close_to_next_map_grid (
391
403
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 )) {
393
405
return true ;
394
406
}
395
407
if (is_close_to_next_map_grid (
396
408
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 )) {
398
410
return true ;
399
411
}
400
412
401
413
return false ;
402
414
}
403
415
void VoxelGridDynamicMapLoader::timer_callback ()
404
416
{
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_;
407
421
}
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) {
411
424
return ;
412
425
}
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 ()) ;
418
431
}
432
+ last_updated_position_ = current_position;
419
433
}
420
434
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)
422
438
{
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) {
426
440
return true ;
427
441
}
428
442
return false ;
0 commit comments