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

ROSRate to be useless without chain to clock pointer #2307

Closed
AlexeyMerzlyakov opened this issue Sep 12, 2023 · 4 comments
Closed

ROSRate to be useless without chain to clock pointer #2307

AlexeyMerzlyakov opened this issue Sep 12, 2023 · 4 comments

Comments

@AlexeyMerzlyakov
Copy link
Contributor

AlexeyMerzlyakov commented Sep 12, 2023

In #2123 there was added new interface: optional pointer to the rclcpp::Clock in Rate class, which could make it to operate with any type of clock; and derivative WallRate and ROSRate classes operating with clocks of RCL_STEADY_TIME and RCL_ROS_TIME types respectively.

However, without of having back the pointer to the clock created inside ROSRate class, the rate became to be useless having no respect to ROS simulated time and publishing to the /clock topic. Indeed, the subscription to /clock is being implemented in rclcpp::TimeSource class that correcting all attached clocks each time when new message from clock topic is arrived. Thus, to make ROSRate to operate in the same way as Rate with given custom clocks, we need to return back rclcpp::Clock pointer from ROSRate and then do something with it (e.g. attach the given clock to the TimeSource operating with selected node where use_sim_time parameter applied).

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22.04
  • Installation type:
    • ROS2 rolling built from sources
  • Version or commit hash:
  • DDS implementation:
    • Checked on Fast-RTPS (default)
  • Client library (if applicable):
    • rclcpp + rcl

Steps to reproduce issue

Steps to reproduce:

  1. Build attached test_ws.zip workspace
  2. Setup on local test workspace $ source test_ws/install/setup.bash
    and run launch-script, that will bring-up testing node along with Gazebo simulation:
$ ros2 launch test_pkg test_node.launch.py

Default outputs for 2Hz rate are 0.5 seconds per each duration (measured in real and ROS time):

[test_node-3] [INFO] [1694521064.567825994] [test_node]: Custom ROS clock ratetime Real: 0.502854 ROS: 0.502000
  1. In Gazebo classic simulator open left pane -> Physics -> decrease "real time update rate" from 1000 -> to 500
  2. Observe what's changed

Expected behavior

When using custom_rate with custom clock:

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
rclcpp::Rate::SharedPtr custom_rate = std::make_shared<rclcpp::Rate>(2.0, clock);

... attached to the TimeSource that subscribing to the /clock:

rclcpp::TimeSource time_source(shared_from_this());
time_source.attachClock(clock);

... and operating through the node where "use_sim_time" parameter is being targeted

start_test_cmd = Node(
    package='test_pkg',
    executable='test_node',
    ...
    parameters=[{'use_sim_time': True}])

... the timing will be as expected:

[test_node-3] [INFO] [1694515774.838433922] [test_node]: Custom ROS clock ratetime Real: 1.000162 ROS: 0.500000

<- CORRECT: duration in ROS clock between two ticks shouldn't be changed, while real time slowed down twice

Actual behavior

When using just ROSRate (uncomment ros_rate and comment back custom_rate lines in a src/test_node.cpp):

rclcpp::ROSRate::SharedPtr ros_rate = std::make_shared<rclcpp::ROSRate>(2.0);

...with default initialized clock, ROSRate won't respect simulation time:

[test_node-3] [INFO] [1694515036.686451392] [test_node]: ROS ratetime Real: 0.499633 ROS: 0.252000

<- INCORRECT: duration in ROS shouldn't be changed

Implementation considerations

There are three different solutions I'd see from this point of view:

Solution 1
Add new rclcpp::Clock::SharedPtr Rate::getClock() method to the Rate (or RateBase) in order to give developer an ability to get clock_ back and later manually attach it in the target code by using

rclcpp::TimeSource time_source(node);
time_source.attachClock(clock);

... or similar construction

Solution 2
Add node pointer optional parameter to the ROSRate constructor and do the same TimeSource(node)->attachClock(clock) chain inside ROSRate, that will hide unnecessary operations from end-developers. However, this might break the overall API logic: why do we need both Clock and Node pointers, if I could get the the clock from node by addressing node->get_clock() method? If so, the ROSRate in this case will not be different from just calling Rate with custom clock argument.

So, therefore moving to the
Solution 3
Completely remove ROSRate from rate.hpp. If someone wants to use ROS-respective rate in his node, it could be a Rate with clock pointer already attached to this node:

auto rate = std::make_shared<rclcpp::Rate>(10.0, node_->get_clock());

and thus, ROSRate is unnecessary in this case.

From my point of view, I'd prefer Solution1 or Solution3, but anyway, this should be discus-sable before the fix to be applied.

@SteveMacenski
Copy link
Collaborator

Yicks, good to point that out

I like solution 3 from an end user API perspective. Messing with time sources should not be required for standard application code to benefit from ROS time -- any method that would require that would break my soul.

Instead of just deleting it, we could shape it elsewhere. For instance: node->create_rate(double hz) analog to other create_*() factories in Node and rclcpp::. That could implicitly use this->get_clock() which is or isn't already set by use sim time.

@alsora
Copy link
Collaborator

alsora commented Sep 14, 2023

+1 for solution 3

@AlexeyMerzlyakov
Copy link
Contributor Author

AlexeyMerzlyakov commented Sep 21, 2023

Okay, I got it. The idea with making the analogue of node->create_timer(), but for rate: create_rate() seems good for me. However, I'd like to be consistent and separate rclcpp::ROSRate removal and node->create_rate() tasks into two PR tickets, since I am not sure that I will have a room for adding new API right now. But I believe to remove unused API from RCLCPP is higher prio. task (to avoid end-developers to use it).

@fujitatomoya
Copy link
Collaborator

I will go ahead to close this in favor of #2326

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants