Skip to content

Commit

Permalink
fix(compare_map_filter): deadlock bug fix (autowarefoundation#10222)
Browse files Browse the repository at this point in the history
* fix(compare_map_filter): deadlock bug fix

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>

* fix: change to lock_guard

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>

* fix: CI error

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>

* reduce scope of mutex

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>

* refactor

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>

* chore: refactor

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>

* fix: add missing mutex for map_grid_size_x

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>

---------

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
  • Loading branch information
badai-nguyen authored and SakodaShintaro committed Mar 10, 2025
1 parent 672897b commit b420cef
Show file tree
Hide file tree
Showing 7 changed files with 152 additions and 117 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -72,39 +72,40 @@ bool DistanceBasedStaticMapLoader::is_close_to_map(
}
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;
{
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_));

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

DistanceBasedCompareMapFilterComponent::DistanceBasedCompareMapFilterComponent(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,11 @@ class DistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader
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;
}

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 VoxelBasedApproximateStaticMapLoader::is_close_to_map(
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_));

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

VoxelBasedApproximateCompareMapFilterComponent::VoxelBasedApproximateCompareMapFilterComponent(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,25 +80,29 @@ bool VoxelDistanceBasedStaticMapLoader::is_close_to_map(
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_));

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 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader
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;
}

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 @@ -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_);
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_next_map_grid(
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_);
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_;
// 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));

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

// 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::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
current_position = current_position_;
}
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(
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)
{
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

0 comments on commit b420cef

Please sign in to comment.