Skip to content

Commit

Permalink
chore: minimize mutex scope
Browse files Browse the repository at this point in the history
Signed-off-by: badai-nguyen <[email protected]>
  • Loading branch information
badai-nguyen committed Oct 20, 2024
1 parent cd70d8d commit 7bed7df
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ void DistanceBasedStaticMapLoader::onMapCallback(
pcl::PointCloud<pcl::PointXYZ> map_pcl;
pcl::fromROSMsg<pcl::PointXYZ>(*map, map_pcl);
const auto map_pcl_ptr = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(map_pcl);
std::lock_guard<std::mutex> lock(static_map_loader_mutex_);
std::unique_lock<std::mutex> lock(static_map_loader_mutex_);
map_ptr_ = map_pcl_ptr;
*tf_map_input_frame_ = map_ptr_->header.frame_id;
if (!tree_) {
Expand All @@ -43,6 +43,7 @@ void DistanceBasedStaticMapLoader::onMapCallback(
}
}
tree_->setInputCloud(map_ptr_);
lock.unlock();
}

bool DistanceBasedStaticMapLoader::is_close_to_map(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@ namespace autoware::compare_map_segmentation
bool VoxelBasedApproximateStaticMapLoader::is_close_to_map(
const pcl::PointXYZ & point, [[maybe_unused]] const double distance_threshold)
{
std::lock_guard<std::mutex> lock(static_map_loader_mutex_);
if (voxel_map_ptr_ == NULL) {
return false;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -261,12 +261,13 @@ void VoxelGridStaticMapLoader::onMapCallback(
pcl::fromROSMsg<pcl::PointXYZ>(*map, map_pcl);
const auto map_pcl_ptr = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(map_pcl);
*tf_map_input_frame_ = map_pcl_ptr->header.frame_id;
std::lock_guard<std::mutex> lock(static_map_loader_mutex_);
std::unique_lock<std::mutex> lock(static_map_loader_mutex_);
voxel_map_ptr_.reset(new pcl::PointCloud<pcl::PointXYZ>);
voxel_grid_.setLeafSize(voxel_leaf_size_, voxel_leaf_size_, voxel_leaf_size_z_);
voxel_grid_.setInputCloud(map_pcl_ptr);
voxel_grid_.setSaveLeafLayout(true);
voxel_grid_.filter(*voxel_map_ptr_);
lock.unlock();

if (debug_) {
publish_downsampled_map(*voxel_map_ptr_);
Expand Down

0 comments on commit 7bed7df

Please sign in to comment.