Skip to content
Closed
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: 0 additions & 2 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1230,8 +1230,6 @@ controller_interface::return_type ControllerManager::update(

for (auto loaded_controller : rt_controller_list)
{
// TODO(v-lopez) we could cache this information
// https://github.com/ros-controls/ros2_control/issues/153
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

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

This issue was closed

if (is_controller_active(*loaded_controller.c))
{
auto controller_update_rate = loaded_controller.c->get_update_rate();
Expand Down
6 changes: 4 additions & 2 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,17 +41,19 @@ int main(int argc, char ** argv)
RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", cm->get_update_rate());

rclcpp::Time begin = cm->now();
rclcpp::Time begin_last = begin;
rclcpp::Time end = begin;

// Use nanoseconds to avoid chrono's rounding
std::this_thread::sleep_for(std::chrono::nanoseconds(1000000000 / cm->get_update_rate()));
while (rclcpp::ok())
{
rclcpp::Time begin_last = begin;
begin = cm->now();
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

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

Start the timer right at the beginning of the new iteration

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

This does seem like a better order.

cm->read();
Comment on lines 51 to 52
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

I think we should rather use something like this:

Suggested change
begin = cm->now();
cm->read();
cm->read();
begin = cm->now();

In this case, only update method is not counted in the period. This is not 100% exact when having multiple controller but closer to the real value.

cm->update(begin, begin - begin_last);
begin_last = begin;
cm->write();
rclcpp::Time end = cm->now();
end = cm->now();
std::this_thread::sleep_for(std::max(
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

This looks like it would cause the time to drift each loop since it's sleeping for a fixed amount of time instead of until the end of the period. Would ros::rate work here? Or setting a hard end time at the beginning of each loop based on the original start? I can test that out if it seems like a reasonable approach.

Copy link
Copy Markdown
Contributor Author

@AndyZe AndyZe Feb 15, 2022

Choose a reason for hiding this comment

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

If you look at L35, there's a comment about why rclcpp::Rate::sleep() isn't used.

What's here seems fine to me but please feel free to test out your other idea. 👍 This still isn't working as well as I'd hope for. (It's not clear if this bit of code is the cause, though)

std::chrono::nanoseconds(0),
std::chrono::nanoseconds(1000000000 / cm->get_update_rate()) -
Expand Down