Open Pansamic opened 11 months ago
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:
#include <rmw_microros/rmw_microros.h>
// Sync timeout const int timeout_ms = 1000;
// Synchronize time with the agent rmw_uros_sync_session(timeout_ms);
2. Get the Synchronized Time
```C
#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);
Detailed Description
I use
rmw_uros_sync_session()
to sync time with Micro-ROS-Agent. But when I usermw_uros_epoch_millis()
andrmw_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()
inmicro_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 callclock_gettime()
and get time from RTC. Actually this method introduces huge latency.Question