Time synchronisation between ROS2 and Gazebo

Using a ROS compatible physics simulator such as Gazebo allows to quickly iterate and test robot control software without requiring actual robotic hardware. Furthermore, robotic prototypes, even if available, are usually limited in numbers. Using a simulator eliminates this constraint by replacing the actual physical prototype with a virtual prototype simulated in software.

When working with virtual prototypes a number of caveats need to be carefully considered. One important subject is time synchronisation between ROS2 robot control software and the virtual robot simulated within Gazebo. Depending on simulation computing requirements and specification of the simulation computer time may progress faster or slower inside the simulator compared to outside. Consequently we need time synchronisation between simulator time and the time used for triggering actions within ROS2 nodes. At the same time it should be possible to use the same robot control software inside a real physical robot, without any need for source code modification.

Note: The content of this article applies to ROS2 Humble Hawksbill with Gazebo Fortress 6.16.0. Same or similar principles apply to other versions of ROS2 and Gazebo, though the specific implementation details may differ.

Let’s take a look at the action items required to enable seamless time synchronisation between ROS2 and Gazebo:

Replace std::chrono::steady_clock/system_clock/... with rclcpp::Clock

std::chrono, a C++ library specialised in dealing with dates and times, is available since C++11. In my observation adoption of new language features for most C++ developers matches the slow speed of new features being added to the C++ programming language itself.

Note: While I see critically the former, I can find no fault with the latter. Dear God ISO C++ committee please save us from turning the C++ standard library into another API and ABI backwards compatibility breaking nightmare.

And while I suspect there are still quite many programmers out there obtaining time the C way ( time_t now = time(NULL); ) at least some software engineers have made the transition to modern C++ ( auto const now = std::chrono::system_clock::now(); ). However, there is no rest for the weary: if you want to seamlessly integrate your ROS2 robot control software with Gazebo you need to update your code again to replace std::chrono::... with rclcpp::Clock, rclcpp::Time and rclcpp::Duration.

Obtaining a ROS2 clock is done by instantiating a rclcpp::Clock object. A single constructor parameter is used to determine the requested clock source: RCL_ROS_TIME, RCL_SYSTEM_TIME and RCL_STEADY_TIME.

-auto const now = std::chrono::steady_clock::now();
+auto const clock = rclcpp::Clock(RCL_STEADY_TIME);
+rclcpp::Time const now = clock.now();

When no parameter is specified RCL_SYSTEM_TIME is used as default clock source. If you want to obtain a clock inside a class derived from rclcpp::Node you can obtain a shared pointer to a RCL_ROS_TIME (default clock selection when instantiating a rclcpp::Node) clock via the get_clock() or now() member functions.

rclcpp::Time const now = this->get_clock()->now();
/* ... same as ... */
rclcpp::Time const now = this->now();
/* ... same as ... */
rclcpp::Time const now = node.get_clock()->now();
/* ... same as ... */
rclcpp::Time const now = node.now();

Let’s take a closer look at the differences between RCL_ROS_TIME, RCL_SYSTEM_TIME and RCL_STEADY_TIME:

RCL_SYSTEM_TIME provides an absolute system time and can be semantically compared to the time provided by your watch. However, just as you adjust the date or time on your watch if you are travelling to a different time zone or due to daylight saving time (DST) the time provided by RCL_SYSTEM_TIME can move both forwards and backwards.

RCL_STEADY_TIME is guaranteed to only move forward – such a clock is known as a monotonic clock. This is necessary if you implement discrete time interval control as a sudden change of the clock (in either direction) would lead to a large error in computation.

RCL_ROS_TIME defaults to RCL_SYSTEM_TIME when not used within a simulation (more on how to tell a ROS2 node that it should be using simulation time in the next section), otherwise it is synchronised to the clock signal provided by the Gazebo simulator.

Finally, operator overloading for both rclcpp::Time and rclcpp::Duration enable time calculation and manipulation quite similar to std::chrono:

auto const clock = rclcpp::Clock(RCL_STEADY_TIME);
rclcpp::Time const start = clock.now();
/* ... */
rclcpp::Time const stop = clock.now();
auto const rclcpp_duration = (stop - start);
auto const chrono_duration = rclcpp_duration.to_chrono<std::chrono::milliseconds>();

Set ROS node parameter use_time_time to true

Every ROS node has a boolean parameter named use_sim_time. If use_sim_time is set to true timestamps obtained via rclcpp::Clock(RCL_ROS_TIME) are no longer obtained from the system clock but from the simulation clock published to the /clock topic. Messages published to /clock are of the type rosgraph_msgs/Clock :

builtin_interfaces/msg/Time clock

which in turn contains a builtin_interfaces/Time message :

int32 sec
uint32 nanosec

. There are several ways of setting the – always available – use_sim_time parameter of a node. One is to directly pass the parameter via command line when starting the a specific node:

ros2 run rviz2 rviz2 --ros-args -p use_sime_time:=true

Another option would be to set use_sim_time using ros2 param set:

ros2 param set /rviz2 use_sim_time true

Since there’s usually a launch file dedicated to bringing up a Gazebo simulation use_sim_time can be also passed via launch file parameter – either directly to a node …

    rviz2 = Node(
        package='rviz2',
        executable='rviz2',
        parameters=[
            {'use_sim_time': True},
        ]
    )

… or indirectly by passing it to another package’s launch file:

    # gazebo_bringup/launch/gazebo.py
    pkg_my_node = get_package_share_directory('my_node')

    my_node = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(os.path.join(pkg_my_node, 'launch', 'my_node_launch.py')),
        launch_arguments={'is_gazebo_sim': 'True'}.items(),
    )

    # my_node/launch/my_node_launch.py
    use_sim_time = LaunchConfiguration('use_sim_time')
    is_use_sim_time_arg = DeclareLaunchArgument('use_sim_time', default_value='False')

    return LaunchDescription([
        is_use_sim_time_arg,
        Node(
            package='my_node',
            parameters=[
                {'use_sim_time': use_sim_time},
            # ...
            ],
        )
    ])

Bridge Gazebo clock messages from Gazebo to ROS2

Once Gazebo is running its simulation time updates must be “bridged” to the dedicated ROS2 /clock topic. This is because Gazebo is publishing simulation time updates using its own (and separate from ROS) transport mechanisms and topics. Let’s first check the existence and update rate of the Gazebo simulation time updates using ign topic --list and ign topic --echo --topic /clock.

ign topic --list
  /clock
  ...

After verifying that simulation time updates are published to the Gazebo /clock topic we need to forward those simulation time updates information to the ROS2 /clock topic. This can be achieved by launching a parameter_bridge (which is part of ros_gz_bridge).

    # gazebo_bringup/launch/gazebo.py
    gazebo_ros_bridge = Node(
        package='ros_gz_bridge',
        executable='parameter_bridge',
        output='screen',
        parameters=[
            {'config_file': os.path.join(get_package_share_directory('gazebo_bringup'), 'config', 'ros_gz_bridge.yaml')},
        ]
    )

Although the topics to be forwarded can be specified as node launch parameters it is easier to specify topic names, topic types and direction by using a dedicated YAML configuration file.

- ros_topic_name: "/clock"
  gz_topic_name: "/clock"
  ros_type_name: "rosgraph_msgs/msg/Clock"
  gz_type_name: "gz.msgs.Clock"
  direction: GZ_TO_ROS

Finally we need to check if the ROS Gazebo bridge works by examining if simulation time updates are published to the ROS2 /clock topic using ros2 topic list and ros2 topic echo /clock:

ros2 topic list
  /clock
  ...

Alexander Entinger is a highly experienced embedded engineer with a focus on robotic systems. By providing hard-won expertise designing embedded systems for real-world embedded applications Alexander Entinger is helping companies developing robotic systems or components for robotic systems to achieve their desired business outcomes.




Leave a Reply

Your email address will not be published.


Comment


Name

Email

Url