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

Conversation

mbuijs
Copy link
Contributor

@mbuijs mbuijs commented Oct 5, 2020

Basic Info

Info Please fill out this column
Ticket(s) this addresses -
Primary OS tested on Ubuntu
Robotic platform tested on simulation

Description of contribution in a few bullet points

  • rclcpp::Rate is used for controlling the frequency in a few parts of the code.
  • rclcpp::Rate uses std::chrono::system_clock which is meant to represent wall time. Due to unevitable clock drift on the local system in combination with time synchronisation mechnism's like NTP this clock can tick at a slower or faster rate to stay synchronized with the actual wall time or even jump both forwards and backwards in time in case of bigger offsets.
  • rclcpp::Rate does not have a mechanism to deal with time jumps, so for example if the time jumps backwards 10 seconds, it will wait for 10 seconds plus the configured interval of the Rate.

This contribution changes the use of rclcpp::Rate to rclcpp::GenericRate<std::chrono::steady_clock> to use the monotonic steady_clock instead. This clock never jumps and is better suited for measuring intervals.

A possible point of discussion would be why I did not use rclcpp::WallRate, which is an alias for rclcpp::GenericRate<std::chrono::steady_clock>. The reason is that I find the name WallRate very misleading, since steady_clock specifically does not follow wall time. In my opinion it should be renamed to SteadyRate or something like that, but that's a different discussion.

Description of documentation updates required from your changes

N/A. (?)

Therefore use rclcpp::GenericRate<std::chrono::steady_clock> instead of
rclcpp::Rate

Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>
@SteveMacenski
Copy link
Member

Thank you for your detailed explanation. After a little bit of digging, I agree with your assessment.

Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

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

I'd prefer WallRate since rclcpp gives that to us and makes this code more readable. When I google things, it seems that this is an accurate use of the Wall phrasing. I will merge when WallRate.

@mbuijs
Copy link
Contributor Author

mbuijs commented Oct 5, 2020

I'd prefer WallRate since rclcpp gives that to us and makes this code more readable. When I google things, it seems that this is an accurate use of the Wall phrasing. I will merge when WallRate.

I'm a bit surprised that you found this an accurate use of the term 'wall' then googling. Among the results I ended up at were man pages and cppreference, which both specifically mentioned that these wall clocks can jump. Then I checked how this is done in ROS1 and I found that there also ros::Rate and ros::WallRate are both linked to system_clock with the only difference being that ros::Rate is linked to ROS time in case use_sime_time is enabled. All findings combined, I decided to create a PR on rclcpp for renaming rclcpp::WallRate to rclcpp::SteadyRate: ros2/rclcpp#1373. This needs some more work though and likely some discussion on how to proceed.

I will change this PR to use rclcpp::WallRate if you insist, but I wanted to double check beforehand.

Side note: I'm wondering if in the long run it would be a better idea to not use Rate and it's specializations at all and switch to using timers instead. It's a bit more code, but in my experience ends up more aligned with how other asynchronous code is written.

@SteveMacenski
Copy link
Member

Yes, please use the ROS2 provided APIs where they exist to make things more readable. I'd be happy to have it changed to another name if that change is made in rclcpp (I don't really have a strong feeling one way or another).

Timers have their roles, but not in the places where you made changes.

@mbuijs
Copy link
Contributor Author

mbuijs commented Oct 5, 2020

Done.

Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>
@SteveMacenski
Copy link
Member

I'll merge after CI passes

@codecov
Copy link

codecov bot commented Oct 5, 2020

Codecov Report

Merging #2012 into main will decrease coverage by 0.61%.
The diff coverage is 100.00%.

Impacted file tree graph

@@            Coverage Diff             @@
##             main    #2012      +/-   ##
==========================================
- Coverage   84.95%   84.33%   -0.62%     
==========================================
  Files         294      294              
  Lines       15056    15056              
==========================================
- Hits        12791    12698      -93     
- Misses       2265     2358      +93     
Flag Coverage Δ
#project 84.33% <100.00%> (-0.62%) ⬇️

Flags with carried forward coverage won't be shown. Click here to find out more.

Impacted Files Coverage Δ
nav2_controller/src/nav2_controller.cpp 89.23% <100.00%> (-1.35%) ⬇️
nav2_costmap_2d/src/costmap_2d_ros.cpp 87.30% <100.00%> (ø)
...v2_recoveries/include/nav2_recoveries/recovery.hpp 83.52% <100.00%> (-5.89%) ⬇️
nav2_waypoint_follower/src/waypoint_follower.cpp 91.86% <100.00%> (ø)
nav2_util/include/nav2_util/costmap.hpp 0.00% <0.00%> (-100.00%) ⬇️
...vior_tree/test/plugins/action/test_spin_action.cpp 0.00% <0.00%> (-100.00%) ⬇️
...av2_dwb_controller/dwb_critics/src/oscillation.cpp 68.67% <0.00%> (-21.69%) ⬇️
...nclude/nav2_behavior_tree/behavior_tree_engine.hpp 88.88% <0.00%> (-11.12%) ⬇️
...v2_util/include/nav2_util/simple_action_server.hpp 91.87% <0.00%> (-3.75%) ⬇️
... and 4 more

Continue to review full report at Codecov.

Legend - Click here to learn more
Δ = absolute <relative> (impact), ø = not affected, ? = missing data
Powered by Codecov. Last update 64871a7...e7594a2. Read the comment docs.

@SteveMacenski SteveMacenski merged commit 63aa0ad into ros-navigation:main Oct 5, 2020
@mbuijs mbuijs deleted the steady_rate branch October 9, 2020 16:05
SteveMacenski pushed a commit that referenced this pull request Nov 4, 2020
* Controllers should not be influenced by time jumps

Therefore use rclcpp::GenericRate<std::chrono::steady_clock> instead of
rclcpp::Rate

Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>

* Change to using `rclcpp::WallRate` for better readability

Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>
SteveMacenski added a commit that referenced this pull request Nov 4, 2020
* initialize variables in inflation layer (#1970)

* Fix zero waypoints crash (#1978)

* return if the number of waypoints is zero.

* terminate the action.

* Succeed action instead of terminating.

* Add IsBatteryLow condition node (#1974)

* Add IsBatteryLow condition node

* Update default battery topic and switch to battery %

* Fix test

* Switch to sensor_msgs/BatteryState

* Add option to use voltage by default or switch to percentage

* Add sensor_msgs dependency in package.xml

* Make percentage default over voltage

* Update parameter list

* Initialize inflate_cone_ variable. (#1988)

* Initialize inflate_cone_ variable.

* initialize inflate_cone_ based on parameter.

* Increase the sleep time in the tests makes the costmap test always succeed on my machine.

* Add timeouts to all spin_until_future_complete calls (#1998)

* Add timeouts to all spin_until_future_complete calls

Signed-off-by: Sarthak Mittal <sarthakmittal2608@gmail.com>

* Update default timeout value

Signed-off-by: Sarthak Mittal <sarthakmittal2608@gmail.com>

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

* Controllers should not be influenced by time jumps

Therefore use rclcpp::GenericRate<std::chrono::steady_clock> instead of
rclcpp::Rate

Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>

* Change to using `rclcpp::WallRate` for better readability

Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>

* Fix max path cycles for case where map has larger Y dimension than X dimension (#2017)

* Fix max path cycles for case where map has larger Y dimension than X dimension

* Improve readability

* fix ament_cpplint and ament_uncrustify issues

* fix minor cherry pick conflict mistake

* bump version to 0.4.4

Co-authored-by: Michael Ferguson <mfergs7@gmail.com>
Co-authored-by: Wilco Bonestroo <w.j.bonestroo@saxion.nl>
Co-authored-by: Sarthak Mittal <sarthakmittal2608@gmail.com>
Co-authored-by: Martijn Buijs <Martijn.buijs@gmail.com>
Co-authored-by: justinIRBT <69175069+justinIRBT@users.noreply.github.com>
ruffsl pushed a commit to ruffsl/navigation2 that referenced this pull request Jul 2, 2021
…ation#2012)

* Controllers should not be influenced by time jumps

Therefore use rclcpp::GenericRate<std::chrono::steady_clock> instead of
rclcpp::Rate

Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>

* Change to using `rclcpp::WallRate` for better readability

Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants