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 isCurrent in obstacle layer and assure CostmapTopicCollisionChecker only uses current costmaps #4800

Draft
wants to merge 6 commits into
base: main
Choose a base branch
from
Draft
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
4 changes: 1 addition & 3 deletions nav2_costmap_2d/plugins/obstacle_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -539,10 +539,9 @@ ObstacleLayer::updateCosts(
return;
}

// if not current due to reset, set current now after clearing
// set was_reset to false again
if (!current_ && was_reset_) {
was_reset_ = false;
current_ = true;
}

if (footprint_clearing_enabled_) {
Expand Down Expand Up @@ -758,7 +757,6 @@ void
ObstacleLayer::reset()
{
resetMaps();
resetBuffersLastUpdated();
current_ = false;
was_reset_ = true;
}
Expand Down
9 changes: 6 additions & 3 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -535,9 +535,10 @@ Costmap2DROS::mapUpdateLoop(double frequency)
}

auto current_time = now();
if ((last_publish_ + publish_cycle_ < current_time) || // publish_cycle_ is due
(current_time <
last_publish_)) // time has moved backwards, probably due to a switch to sim_time // NOLINT
auto map_current = isCurrent();
if (map_current && // only update costmap if it's current
((last_publish_ + publish_cycle_ < current_time) || // publish_cycle_ is due
(current_time < last_publish_))) // time has moved backwards, probably due to a switch to sim_time // NOLINT
{
RCLCPP_DEBUG(get_logger(), "Publish costmap at %s", name_.c_str());
costmap_publisher_->publishCostmap();
Expand All @@ -547,6 +548,8 @@ Costmap2DROS::mapUpdateLoop(double frequency)
}

last_publish_ = current_time;
} else if (!map_current) {
RCLCPP_WARN(get_logger(), "Costmap was not published because it`s not current");
}
}
}
Expand Down
Loading