Skip to content

Commit

Permalink
Set map_received to true
Browse files Browse the repository at this point in the history
  • Loading branch information
Matthew Hansen committed Oct 15, 2019
1 parent 090ddc7 commit 2edfb83
Showing 1 changed file with 4 additions and 0 deletions.
4 changes: 4 additions & 0 deletions nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,7 @@ StaticLayer::getParameters()

// Enforce bounds
lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
map_received_ = false;
}

void
Expand Down Expand Up @@ -241,6 +242,9 @@ StaticLayer::incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
{
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
processMap(*new_map);
if (!map_received_) {
map_received_ = true;
}
}

void
Expand Down

0 comments on commit 2edfb83

Please sign in to comment.