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

Controllers should not be influenced by time jumps or slew #2012

Merged
merged 2 commits into from
Oct 5, 2020
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
2 changes: 1 addition & 1 deletion nav2_controller/src/nav2_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -283,7 +283,7 @@ void ControllerServer::computeControl()
setPlannerPath(action_server_->get_current_goal()->path);
progress_checker_->reset();

rclcpp::Rate loop_rate(controller_frequency_);
rclcpp::WallRate loop_rate(controller_frequency_);
while (rclcpp::ok()) {
if (action_server_ == nullptr || !action_server_->is_server_active()) {
RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping.");
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -382,7 +382,7 @@ Costmap2DROS::mapUpdateLoop(double frequency)

RCLCPP_DEBUG(get_logger(), "Entering loop");

rclcpp::Rate r(frequency); // 200ms by default
rclcpp::WallRate r(frequency); // 200ms by default

while (rclcpp::ok() && !map_update_thread_shutdown_) {
nav2_util::ExecutionTimer timer;
Expand Down
2 changes: 1 addition & 1 deletion nav2_recoveries/include/nav2_recoveries/recovery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,7 @@ class Recovery : public nav2_core::Recovery
// Initialize the ActionT result
auto result = std::make_shared<typename ActionT::Result>();

rclcpp::Rate loop_rate(cycle_frequency_);
rclcpp::WallRate loop_rate(cycle_frequency_);

while (rclcpp::ok()) {
if (action_server_->is_cancel_requested()) {
Expand Down
2 changes: 1 addition & 1 deletion nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ WaypointFollower::followWaypoints()
return;
}

rclcpp::Rate r(loop_rate_);
rclcpp::WallRate r(loop_rate_);
uint32_t goal_index = 0;
bool new_goal = true;

Expand Down