0
$\begingroup$

I wrote the following code to check the difference myself, but I could not find any considerable difference.

#include <rclcpp/rclcpp.hpp>

auto main(int argc, char **argv) -> int 
{
        rclcpp::init(argc, argv);

        auto node = std::make_shared<rclcpp::Node>("time_converter");

        rclcpp::Time steady_time(node->now(),RCL_STEADY_TIME);
        RCLCPP_INFO(node->get_logger(), "RCL_STEADY_TIME = %f",steady_time.seconds());  

        rclcpp::Time sys_time(node->now(),RCL_SYSTEM_TIME);
        RCLCPP_INFO(node->get_logger(), "RCL_SYSTEM_TIME = %f",sys_time.seconds());  

        rclcpp::Time ros_time(node->now(),RCL_ROS_TIME);
        RCLCPP_INFO(node->get_logger(), "RCL_ROS_TIME = %f",ros_time.seconds());  

        return EXIT_SUCCESS;
}

Output:

[INFO] [1699543136.456027415] [time_converter]: steady node time = 1699543136.456026
[INFO] [1699543136.456121797] [time_converter]: sys node time = 1699543136.456121
[INFO] [1699543136.456138399] [time_converter]: sys node time = 1699543136.456138

Actual question is, How do I get steady time from node->now()? Because that is the answer I am looking for.

$\endgroup$

1 Answer 1

1
$\begingroup$

The documentation on the different time sources is here:

There will be at least three versions of these abstractions with the following types, SystemTime, SteadyTime and ROSTime. These choices are designed to parallel the std::chrono system_clock and steady_clock.

[...]

The ROSTime will report the same as SystemTime when a ROS Time Source is not active. When the ROS time source is active ROSTime will return the latest value reported by the Time Source. ROSTime is considered active when the parameter use_sim_time is set on the node.

For the difference between std::chrono::system_clock and std::chrono::steady_clock, see this stackverflow answer:

If you're holding a system_clock in your hand, you would call it a watch, and it would tell you what time it is.

If you're holding a steady_clock in your hand, you would call it a stopwatch, and it would tell you how fast someone ran a lap, but it would not tell you what time it is.

If you had to, you could time someone running a lap with your watch. But if your watch (like mine) periodically talked to another machine (such as the atomic clock in Boulder CO) to correct itself to the current time, it might make minor mistakes in timing that lap. The stopwatch won't make that mistake, but it also can't tell you what the correct current time is.

Re. your second question:

Actual question is, How do I get steady time from node->now()? Because that is the answer I am looking for.

~~I think ROS node clocks always use RCL_ROS_TIME which either is SystemTime or the time that is published to topic /clock in case of use_sim_time true.~~

EDIT: Seems above is wrong, see the source code: the Node constructor takes the clock type from the NodeOptions. So it seems it is possible to choose the clock type by instantiatin a NodeOptions, set its clock type and pass it to your node constructor. See here for the options in the NodeOptions. /EDIT

What is your exact use case to want to set the node clock to steady time?

If you actually want a steady timer:

You can create use Node::create_wall_timer() instead of Node::create_timer(), e.g.:

timer_ = this->create_wall_timer(
      500ms, std::bind(&MinimalPublisher::timer_callback, this));

A wall timer uses RCL_STEADY_TIME:

https://github.com/ros2/rclcpp/blob/0f331f90a99da40f7b7a69b4f55b30b7245d294f/rclcpp/include/rclcpp/timer.hpp#L347

Do realize that if you use a wall_timer in a node that is also used with use_sim_time == true, its timer will run and the timer callback will be triggered irrespective of the simulation time (e.g. also when the simulation is paused).

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.