micro-ROS/micro_ros_stm32cubemx_utils

Cannot sync accurate time

Pansamic opened this issue · 3 comments

Detailed Description

I use rmw_uros_sync_session() to sync time with Micro-ROS-Agent. But when I use rmw_uros_epoch_millis() and rmw_uros_epoch_nanos() to get time, I got seconds starting from 0, not 170xxxxxx (Linux timestamp seconds) as expected.

Thinking

This result was no surprise because I cannot find any API that can change local time of MCU, while there is an API to get time called clock_gettime() in micro_ros_stm32cubemx_utils/extra_sources/microros_time.c.

I want Micro-ROS to set local time that high accuracy hardware timer ( DWT, TIM or RTC ) holds, rather than FreeRTOS ticks.

it's said that rmw_uros_sync_session() uses NTP to sync time so it must has high accurate and less latency, but it cannot function properly, pity.

Trials

My clock_gettime() is now modified to set RTC time. Micro-ROS subscribes /time_reference topic from Micro-ROS-Agent and transform timestamp to RTC Binary format. I use the following code to get current timestamp and it works well (superficially). This function seems to call clock_gettime() and get time from RTC. Actually this method introduces huge latency.

rcutils_time_point_value_t current_time;
rcutils_ret_t ret;
ret = rcutils_system_time_now(&current_time);
if(ret != RCUTILS_RET_OK)
    printf("[ERROR]read systime failed!\r\n");
msg->header.stamp.sec = RCUTILS_NS_TO_S(current_time);
msg->header.stamp.nanosec = (uint32_t)current_time;

Question

  1. How does Micro-ROS set time?
  2. Can maintainers expose some API to set local time?

How does Micro-ROS set time?

rmw_uros_sync_session will not change your local time it just stores a time offset of the XRCE session that is used when rmw_uros_epoch_nanos and rmw_uros_epoch_millis are called.

Can maintainers expose some API to set local time?

Out of micro-ROS scope.

Hi @Pansamic,

Were you able to find a solution for the time synchronization issue? I'm facing a similar challenge, as I need to timestamp all the messages published by a micro-ROS node running on an MCU.

@pablogs9, could you please advise on the recommended approach for timestamping messages within a micro-ROS node?

Best Regards

If anyone stumbles upon this issue looking for a way to timestamp messages in micro-ROS, here's a solution that worked for me:

  1. Synchronize the Time with the Agent
#include <rmw_microros/rmw_microros.h>

// Sync timeout
const int timeout_ms = 1000;

// Synchronize time with the agent
rmw_uros_sync_session(timeout_ms);
  1. Get the Synchronized Time
#include <rmw_microros/rmw_microros.h>

// Get corrected epoch time 
int64_t time_ns = rmw_uros_epoch_nanos();

// Convert to required format
msg.header.stamp.sec = (int32_t)(time_ns / 1000000000);
msg.header.stamp.nanosec = (uint32_t)(time_ns % 1000000000);