Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(compare_map_filter): deadlock bug fix #10222

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -72,39 +72,40 @@
}
return true;
}

bool DistanceBasedDynamicMapLoader::is_close_to_map(
const pcl::PointXYZ & point, const double distance_threshold)
{
if (current_voxel_grid_dict_.size() == 0) {
return false;
}
if (!isFinite(point)) {
return false;
}
std::shared_ptr<pcl::search::Search<pcl::PointXYZ>> map_cell_kdtree;

Check warning on line 78 in perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp#L78

Added line #L78 was not covered by tests
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
if (current_voxel_grid_dict_.size() == 0) {
return false;
}
if (!isFinite(point)) {
return false;
}

const int 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_));
const int 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_));

Check warning on line 90 in perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp#L88-L90

Added lines #L88 - L90 were not covered by tests

if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
return false;
}
if (current_voxel_grid_array_.at(map_grid_index) != nullptr) {
if (current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree == nullptr) {
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
return false;
}
std::vector<int> nn_indices(1);
std::vector<float> nn_distances(1);
if (!current_voxel_grid_array_.at(map_grid_index)
->map_cell_kdtree->nearestKSearch(point, 1, nn_indices, nn_distances)) {
const auto & current_voxel_grid = current_voxel_grid_array_.at(map_grid_index);
if (current_voxel_grid == nullptr) {
return false;
}
if (nn_distances[0] <= distance_threshold) {
return true;
}
map_cell_kdtree = current_voxel_grid->map_cell_kdtree;
}
return false;

std::vector<int> nn_indices(1);
std::vector<float> nn_distances(1);
if (!map_cell_kdtree->nearestKSearch(point, 1, nn_indices, nn_distances)) {
return false;
}

return nn_distances[0] <= distance_threshold;

Check warning on line 108 in perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp#L108

Added line #L108 was not covered by tests
}

DistanceBasedCompareMapFilterComponent::DistanceBasedCompareMapFilterComponent(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,11 @@
inline void addMapCellAndFilter(
const autoware_map_msgs::msg::PointCloudMapCellWithID & map_cell_to_add) override
{
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;
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
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;

Check warning on line 71 in perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp#L69-L71

Added lines #L69 - L71 were not covered by tests
}

pcl::PointCloud<pcl::PointXYZ> map_cell_pc_tmp;
pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,29 +45,30 @@
bool VoxelBasedApproximateDynamicMapLoader::is_close_to_map(
const pcl::PointXYZ & point, [[maybe_unused]] const double distance_threshold)
{
if (current_voxel_grid_dict_.size() == 0) {
return false;
}
VoxelGridPointXYZ map_cell_voxel_grid;
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
if (current_voxel_grid_dict_.size() == 0) {
return false;
}

const int 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_));
const int 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_));

Check warning on line 57 in perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp#L55-L57

Added lines #L55 - L57 were not covered by tests

if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
return false;
}
if (current_voxel_grid_array_.at(map_grid_index) != nullptr) {
const int index = current_voxel_grid_array_.at(map_grid_index)
->map_cell_voxel_grid.getCentroidIndexAt(
current_voxel_grid_array_.at(map_grid_index)
->map_cell_voxel_grid.getGridCoordinates(point.x, point.y, point.z));
if (index == -1) {
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
return false;
} else {
return true;
}
const auto & current_voxel_grid = current_voxel_grid_array_.at(map_grid_index);
if (current_voxel_grid == nullptr) {
return false;
}
map_cell_voxel_grid = current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid;
}
return false;

const int index = map_cell_voxel_grid.getCentroidIndexAt(
map_cell_voxel_grid.getGridCoordinates(point.x, point.y, point.z));
return (index != -1);

Check warning on line 71 in perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp#L70-L71

Added lines #L70 - L71 were not covered by tests
}

VoxelBasedApproximateCompareMapFilterComponent::VoxelBasedApproximateCompareMapFilterComponent(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,25 +80,29 @@
bool VoxelDistanceBasedDynamicMapLoader::is_close_to_map(
const pcl::PointXYZ & point, const double distance_threshold)
{
if (current_voxel_grid_dict_.size() == 0) {
return false;
}
std::shared_ptr<pcl::search::Search<pcl::PointXYZ>> map_cell_kdtree;
VoxelGridPointXYZ map_cell_voxel_grid;
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
if (current_voxel_grid_dict_.size() == 0) {
return false;
}

const int 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_));
const int 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_));

Check warning on line 93 in perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp#L91-L93

Added lines #L91 - L93 were not covered by tests

if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
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_voxel_grid,
current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree)) {
return true;
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
return false;
}
if (current_voxel_grid_array_.at(map_grid_index) == nullptr) {
return false;
}
map_cell_voxel_grid = current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid;
map_cell_kdtree = current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree;
}
return false;
return is_close_to_neighbor_voxels(
point, distance_threshold, map_cell_voxel_grid, map_cell_kdtree);
}

VoxelDistanceBasedCompareMapFilterComponent::VoxelDistanceBasedCompareMapFilterComponent(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,11 @@
inline void addMapCellAndFilter(
const autoware_map_msgs::msg::PointCloudMapCellWithID & map_cell_to_add) override
{
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;
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
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;

Check warning on line 77 in perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp#L75-L77

Added lines #L75 - L77 were not covered by tests
}

pcl::PointCloud<pcl::PointXYZ> map_cell_pc_tmp;
pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 Autoware Foundation

Check warning on line 1 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: Primitive Obsession

In this module, 42.3% of all function arguments are primitive types, threshold = 30.0%. The functions in this file have too many primitive types (e.g. int, double, float) in their function argument lists. Using many primitive types lead to the code smell Primitive Obsession. Avoid adding more primitive arguments.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -325,15 +325,18 @@
}
void VoxelGridDynamicMapLoader::onEstimatedPoseCallback(nav_msgs::msg::Odometry::ConstSharedPtr msg)
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L328

Added line #L328 was not covered by tests
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.

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

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L337-L339

Added lines #L337 - L339 were not covered by tests
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,77 +355,88 @@
bool VoxelGridDynamicMapLoader::is_close_to_map(
const pcl::PointXYZ & point, const double distance_threshold)
{
if (current_voxel_grid_dict_.size() == 0) {
return false;
}

// Compare point with map grid that point belong to

int 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_));

if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
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)) {
return true;
double origin_x, origin_y, map_grid_size_x, map_grid_size_y;
int map_grids_x, map_grid_index;
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L361

Added line #L361 was not covered by tests
if (current_voxel_grid_dict_.size() == 0) {
return false;
}
origin_x = origin_x_;
origin_y = origin_y_;
map_grid_size_x = map_grid_size_x_;
map_grid_size_y = map_grid_size_y_;
map_grids_x = map_grids_x_;

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L365-L369

Added lines #L365 - L369 were not covered by tests
// Compare point with map grid that point belong to

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));

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L372-L374

Added lines #L372 - L374 were not covered by tests

if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
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,

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L381-L382

Added lines #L381 - L382 were not covered by tests
current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid)) {
return true;
}
}

// 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;
std::optional<geometry_msgs::msg::Point> current_position;

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L417

Added line #L417 was not covered by tests
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
current_position = current_position_;

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L419-L420

Added lines #L419 - L420 were not covered by tests
}
if (last_updated_position_ == std::nullopt) {
request_update_map(current_position_.value());
last_updated_position_ = current_position_;

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(

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L428

Added line #L428 was not covered by tests
current_position.value(), last_updated_position_.value(), map_update_distance_threshold_)) {
request_update_map(current_position.value());

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L430

Added line #L430 was not covered by tests
}
last_updated_position_ = current_position;

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L432

Added line #L432 was not covered by tests
}

bool VoxelGridDynamicMapLoader::should_update_map() const
bool VoxelGridDynamicMapLoader::should_update_map(

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L435

Added line #L435 was not covered by tests
const geometry_msgs::msg::Point & current_point, const geometry_msgs::msg::Point & last_point,
const double map_update_distance_threshold)
{
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
Loading
Loading