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

Open
wants to merge 8 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 2 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 @@ -76,6 +76,7 @@
bool DistanceBasedDynamicMapLoader::is_close_to_map(
const pcl::PointXYZ & point, const double distance_threshold)
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);

Check warning on line 79 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#L79

Added line #L79 was not covered by tests
if (current_voxel_grid_dict_.size() == 0) {
return false;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
bool VoxelBasedApproximateDynamicMapLoader::is_close_to_map(
const pcl::PointXYZ & point, [[maybe_unused]] const double distance_threshold)
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);

Check warning on line 48 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#L48

Added line #L48 was not covered by tests
if (current_voxel_grid_dict_.size() == 0) {
return false;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@
bool VoxelDistanceBasedDynamicMapLoader::is_close_to_map(
const pcl::PointXYZ & point, const double distance_threshold)
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);

Check warning on line 83 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#L83

Added line #L83 was not covered by tests
if (current_voxel_grid_dict_.size() == 0) {
return false;
}
Expand Down
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wait, is the following part in L343 right?
Should we return false when at() function gives nullptr and currently it seems inverted.

if (  static_cast<size_t>(neighbor_map_grid_index) >= current_voxel_grid_array_.size() ||
  neighbor_map_grid_index == current_map_grid_index || current_voxel_grid_array_.at(neighbor_map_grid_index) != nullptr) {
  return false;
}

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@YoshiRi

  • First, the line is unrelated to this PR.
  • Second, it's correct because when there're no map grids (nullprt), all pointcloud will be far from map ( is close to map = False).

Original file line number Diff line number Diff line change
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 = std::nullopt;

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 failure on line 420 in perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp

View workflow job for this annotation

GitHub Actions / cppcheck-differential

Redundant initialization for 'current_position'. The initialized value is overwritten before it is read. [redundantInitialization]

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) 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 @@
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 @@
/** Update loaded map grid array for fast searching*/
virtual inline void updateVoxelGridArray()
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);

Check warning on line 242 in perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp#L242

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

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,19 +279,21 @@
virtual inline void addMapCellAndFilter(
const autoware_map_msgs::msg::PointCloudMapCellWithID & map_cell_to_add)
{
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_) {
RCLCPP_ERROR(
logger_,
"Map was not split or split map grid size is too large. Split map with grid size smaller "
"than %f",
max_map_grid_size_);
}

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_);
{
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 285 in perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp#L283-L285

Added lines #L283 - L285 were not covered by tests
if (map_grid_size_x_ > max_map_grid_size_ || map_grid_size_y_ > max_map_grid_size_) {
RCLCPP_ERROR(
logger_,
"Map was not split or split map grid size is too large. Split map with grid size smaller "
"than %f",
max_map_grid_size_);
}

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

Check warning on line 295 in perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp#L294-L295

Added lines #L294 - L295 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
Loading