Skip to content

Commit

Permalink
fix(compare_map_filter): deadlock bug fix
Browse files Browse the repository at this point in the history
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
  • Loading branch information
badai-nguyen committed Mar 4, 2025
1 parent 9d61ff1 commit 9d844df
Show file tree
Hide file tree
Showing 2 changed files with 48 additions and 26 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -325,15 +325,18 @@ VoxelGridDynamicMapLoader::VoxelGridDynamicMapLoader(
}
void VoxelGridDynamicMapLoader::onEstimatedPoseCallback(nav_msgs::msg::Odometry::ConstSharedPtr msg)
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
current_position_ = msg->pose.pose.position;
}
bool VoxelGridDynamicMapLoader::is_close_to_next_map_grid(
const pcl::PointXYZ & point, const int current_map_grid_index, const double distance_threshold)
const pcl::PointXYZ & point, const int current_map_grid_index, const double distance_threshold,
const double origin_x, const double origin_y, const double map_grid_size_x,
const double map_grid_size_y, const int map_grids_x)
{
int neighbor_map_grid_index = static_cast<int>(
std::floor((point.x - origin_x_) / map_grid_size_x_) +
map_grids_x_ * std::floor((point.y - origin_y_) / map_grid_size_y_));

std::floor((point.x - origin_x) / map_grid_size_x) +
map_grids_x * std::floor((point.y - origin_y) / map_grid_size_y));
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);

Check warning on line 339 in perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Excess Number of Function Arguments

VoxelGridDynamicMapLoader::is_close_to_next_map_grid has 8 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.
if (
static_cast<size_t>(neighbor_map_grid_index) >= current_voxel_grid_array_.size() ||
neighbor_map_grid_index == current_map_grid_index ||
Expand All @@ -352,7 +355,10 @@ bool VoxelGridDynamicMapLoader::is_close_to_next_map_grid(
bool VoxelGridDynamicMapLoader::is_close_to_map(
const pcl::PointXYZ & point, const double distance_threshold)
{
// std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
dynamic_map_loader_mutex_.lock();
if (current_voxel_grid_dict_.size() == 0) {
dynamic_map_loader_mutex_.unlock();
return false;
}

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

if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
dynamic_map_loader_mutex_.unlock();
return false;
}
if (
current_voxel_grid_array_.at(map_grid_index) != nullptr &&
is_close_to_neighbor_voxels(
point, distance_threshold, current_voxel_grid_array_.at(map_grid_index)->map_cell_pc_ptr,
current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid)) {
dynamic_map_loader_mutex_.unlock();
return true;
}

auto origin_x = origin_x_;
auto origin_y = origin_y_;
auto map_grid_size_x = map_grid_size_x_;
auto map_grid_size_y = map_grid_size_y_;
auto map_grids_x = map_grids_x_;
dynamic_map_loader_mutex_.unlock();

// Compare point with the neighbor map cells if point close to map cell boundary

if (is_close_to_next_map_grid(
pcl::PointXYZ(point.x - distance_threshold, point.y, point.z), map_grid_index,
distance_threshold)) {
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
return true;
}

if (is_close_to_next_map_grid(
pcl::PointXYZ(point.x + distance_threshold, point.y, point.z), map_grid_index,
distance_threshold)) {
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
return true;
}

if (is_close_to_next_map_grid(
pcl::PointXYZ(point.x, point.y - distance_threshold, point.z), map_grid_index,
distance_threshold)) {
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
return true;
}
if (is_close_to_next_map_grid(
pcl::PointXYZ(point.x, point.y + distance_threshold, point.z), map_grid_index,
distance_threshold)) {
distance_threshold, origin_x, origin_y, map_grid_size_x, map_grid_size_y, map_grids_x)) {
return true;
}

return false;
}
void VoxelGridDynamicMapLoader::timer_callback()
{
if (current_position_ == std::nullopt) {
return;
}
if (last_updated_position_ == std::nullopt) {
request_update_map(current_position_.value());
last_updated_position_ = current_position_;
dynamic_map_loader_mutex_.lock();
auto current_position = current_position_;
dynamic_map_loader_mutex_.unlock();

if (current_position == std::nullopt) {
return;
}

if (should_update_map()) {
last_updated_position_ = current_position_;
request_update_map((current_position_.value()));
last_updated_position_ = current_position_;
if (
last_updated_position_ == std::nullopt ||
should_update_map(
current_position.value(), last_updated_position_.value(), map_update_distance_threshold_)) {
request_update_map(current_position.value());
}
last_updated_position_ = current_position;
}

bool VoxelGridDynamicMapLoader::should_update_map() const
bool VoxelGridDynamicMapLoader::should_update_map(
const geometry_msgs::msg::Point & current_point, const geometry_msgs::msg::Point & last_point,
const double map_update_distance_threshold) const
{
if (
distance2D(current_position_.value(), last_updated_position_.value()) >
map_update_distance_threshold_) {
if (distance2D(current_point, last_point) > map_update_distance_threshold) {
return true;
}
return false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -190,12 +190,16 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
void onEstimatedPoseCallback(nav_msgs::msg::Odometry::ConstSharedPtr msg);

void timer_callback();
bool should_update_map() const;
bool should_update_map(

Check failure on line 193 in perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp

View workflow job for this annotation

GitHub Actions / cppcheck-differential

inconclusive: Technically the member function 'autoware::compare_map_segmentation::VoxelGridDynamicMapLoader::should_update_map' can be static (but you may consider moving to unnamed namespace). [functionStatic]
const geometry_msgs::msg::Point & current_point, const geometry_msgs::msg::Point & last_point,
const double map_update_distance_threshold) const;
void request_update_map(const geometry_msgs::msg::Point & position);
bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) override;
/** \brief Check if point close to map pointcloud in the */
bool is_close_to_next_map_grid(
const pcl::PointXYZ & point, const int current_map_grid_index, const double distance_threshold);
const pcl::PointXYZ & point, const int current_map_grid_index, const double distance_threshold,
const double origin_x, const double origin_y, const double map_grid_size_x,
const double map_grid_size_y, const int map_grids_x);

inline pcl::PointCloud<pcl::PointXYZ> getCurrentDownsampledMapPc()
{
Expand Down Expand Up @@ -235,6 +239,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
/** Update loaded map grid array for fast searching*/
virtual inline void updateVoxelGridArray()
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
origin_x_ = std::floor((current_position_.value().x - map_loader_radius_) / map_grid_size_x_) *
map_grid_size_x_ +
origin_x_remainder_;
Expand All @@ -253,7 +258,6 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader

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

origin_x_remainder_ = std::remainder(map_cell_to_add.metadata.min_x, map_grid_size_x_);
origin_y_remainder_ = std::remainder(map_cell_to_add.metadata.min_y, map_grid_size_y_);
dynamic_map_loader_mutex_.unlock();

pcl::PointCloud<pcl::PointXYZ> map_cell_pc_tmp;
pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp);
Expand Down

0 comments on commit 9d844df

Please sign in to comment.