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 1 commit
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 @@ -102,6 +102,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name, tf2_ros::Buffer & tf)

// we need to make sure that the transform between the robot base frame
// and the global frame is available
rclcpp::Rate r(10);
Copy link
Contributor

Choose a reason for hiding this comment

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

I'm not sure this is safe. At this point in the code, the node isn't spinning yet. If it's not spinning, the ros clock can't advance when use_sim_time is active. This could deadlock.

It may not be a failure in practice because, last time I checked, Rate used the wall clock instead of the ros clock, however that seems like a bug to me and may change. I'd say we should only make this change if we are confident that Rate objects should always use wall clock time and never the simulation clock.

Copy link
Member Author

@SteveMacenski SteveMacenski May 29, 2019

Choose a reason for hiding this comment

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

From this ticket: https://answers.ros.org/question/319510/rclcpprate-doesnt-use-ros-time-use_sim_time/

I'd venture to say it will not remain that way. However, even if the node hasn't been put in spin, that has never before stopped the ros clock - that's usually been a separate library that can be instantiated separately of even a ros node. I can't think of a reason why the node not yet having called spin would stop the clock.

Copy link
Contributor

Choose a reason for hiding this comment

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

It's not that way anymore. The clock updates come in as a message on the /clock topic and the node has to spin to process that message and advance the clock

At least, that's the way it was a few months ago.

Copy link
Member Author

Choose a reason for hiding this comment

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

Got it, OK. I think all 3 need throttling (especially the service caller). I will redo using non-ros clock implementations.

Thanks for the deep look

while (rclcpp::ok() &&
!tf_.canTransform(global_frame_, robot_base_frame_, tf2::TimePointZero,
tf2::durationFromSec(0.1), &tf_error))
Expand All @@ -116,6 +117,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name, tf2_ros::Buffer & tf)
// 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();
r.sleep();
}

// check if we want a rolling window version of the costmap
Expand Down Expand Up @@ -382,7 +384,7 @@ void 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_) {
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);

rclcpp::Rate r(10);
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
while (!map_gen->saved_map_ && rclcpp::ok()) {
rclcpp::spin_some(map_gen);
rclcpp::sleep_for(100ms);
r.sleep();
}

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 @@ -58,10 +58,12 @@ class ServiceClient

void wait_for_service(const std::chrono::seconds timeout = std::chrono::seconds::max())
{
rclcpp::Rate r(100.);
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
while (!client_->wait_for_service(timeout)) {
if (!rclcpp::ok()) {
throw std::runtime_error("waitForServer: interrupted while waiting for service to appear");
}
r.sleep();
}
}

Expand Down