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

adding rate loops where applicable #743

Merged
merged 4 commits into from
Jul 29, 2019
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
4 changes: 3 additions & 1 deletion nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,6 +171,7 @@ Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/)
std::string tf_error;

RCLCPP_INFO(get_logger(), "Checking transform");
auto sleep_dur = std::chrono::milliseconds(100);
while (rclcpp::ok() &&
!tf_buffer_->canTransform(global_frame_, robot_base_frame_, tf2::TimePointZero,
tf2::durationFromSec(1.0), &tf_error))
Expand All @@ -182,6 +183,7 @@ Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/)
// The error string will accumulate and errors will typically be the same, so the last
// will do for the warning above. Reset the string here to avoid accumulation
tf_error.clear();
rclcpp::sleep_for(sleep_dur);
}

// Create a thread to handle updating the map
Expand Down Expand Up @@ -444,7 +446,7 @@ Costmap2DROS::start()
stop_updates_ = false;

// block until the costmap is re-initialized.. meaning one update cycle has run
rclcpp::Rate r(100.0);
rclcpp::Rate r(20.0);
while (rclcpp::ok() && !initialized_) {
RCLCPP_DEBUG(get_logger(), "Sleeping, waiting for initialized_");
r.sleep();
Expand Down
3 changes: 2 additions & 1 deletion nav2_map_server/src/map_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,9 +99,10 @@ int main(int argc, char ** argv)
auto map_gen = std::make_shared<nav2_map_server::MapGenerator>(mapname, threshold_occupied,
threshold_free);

auto sleep_dur = std::chrono::milliseconds(100);
while (!map_gen->saved_map_ && rclcpp::ok()) {
rclcpp::spin_some(map_gen);
rclcpp::sleep_for(100ms);
rclcpp::sleep_for(sleep_dur);
}

rclcpp::shutdown();
Expand Down
2 changes: 2 additions & 0 deletions nav2_util/include/nav2_util/service_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,11 +110,13 @@ class ServiceClient

void wait_for_service(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds::max())
{
auto sleep_dur = std::chrono::milliseconds(10);
while (!client_->wait_for_service(timeout)) {
if (!rclcpp::ok()) {
throw std::runtime_error(
service_name_ + " service client: interrupted while waiting for service");
}
rclcpp::sleep_for(sleep_dur);
}
}

Expand Down