Skip to main content

Time Synchronization

Overview

Time synchronization is a feature used to synchronize the time of the payload device with the aircraft's time. PSDK synchronizes the time of the payload device with the aircraft equipped with RTK functionality using PPS or NTP. Payload devices with the "Time Synchronization" feature allow users to easily troubleshoot various faults during aircraft flights, analyze sensor sampling data, and obtain accurate positioning information, among other functions.

Terminology

  • Aircraft Time: The time of the aircraft's system.
  • Local Time: The time on the payload device.

Time Synchronization

After the payload device developed with PSDK is installed on the aircraft and powered on, the time synchronization function module will be initialized to eliminate the clock difference between the payload device and the aircraft, synchronizing the time of the payload device and the aircraft.

Note:

  • Before using the time synchronization function, please confirm through the mobile app that the aircraft maintains good communication with the RTK satellites. This mobile app can be Autel Robotics' app such as Autel Enterprise or a mobile app developed based on MSDK.
  1. Install the payload device on the aircraft's gimbal. After the aircraft is powered on, the payload device developed with PSDK will receive the PPS hardware pulse signal sent by the aircraft;
  2. When the payload device detects the rising edge of the PPS signal, it needs to record the local time on the payload device;
  3. The PSDK underlying processing program will retrieve the aircraft's time synchronized with the PPS signal.

    Note

    • Ensure that the delay between the rising edge of the PPS signal reaching the payload and the payload recording the local time is less than 1ms.
    • Use hardware interrupts to respond to the PPS signal.
    1. The PSDK underlying program will calculate the clock difference between the payload device's local time and the aircraft's time, achieving synchronization between the payload device and the aircraft's system time.
  4. The payload device will convert its local time to the aircraft's time using the UAV_TimeSync_TransferToAircraftTime interface.

Using Time Synchronization Feature

1. Initialize the Time Synchronization Module

To use the time synchronization feature, the time synchronization module needs to be initialized.

uavStat = UAV_TimeSync_Init();
if (uavStat != UAV_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("time synchronization module init error.");
return uavStat;
}

uavStat = UAV_TimeSync_SetType(UAV_TIME_SYNC_TYPE_PPS_CLOCK)
if (uavStat != UAV_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("time set sync type error.");
return uavStat;
}

uavStat = UAV_TimeSync_SetType(UAV_TIME_SYNC_TYPE_NTP);
if(uavStat != UAV_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
{
UAV_LOG_ERROR("UAV_TimeSync_SetType failed");
return UAV_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}

2. Develop and Register Function to Retrieve Local Time on Payload Device

When using the time synchronization feature with payload devices developed based on PSDK, the device needs to respond to the PPS time synchronization signal sent by the aircraft in hardware interrupt mode. Upon triggering the latest PPS signal, the payload device's control program must retrieve the local time of the payload device.

  1. Develop and Register Hardware Interrupt Handler Developers must implement the hardware interrupt handling function and register it to the specified interface. When the payload device receives the rising edge of the PPS signal, the hardware interrupt handler will process the PPS time synchronization signal.
void UAV_Test_PpsIrqHandler(void)
{
T_UAVReturnCode psdkStat;
uint32_t timeMs = 0;

/* EXTI line interrupt detected */
if (__HAL_GPIO_EXTI_GET_IT(PPS_PIN) != RESET) {
__HAL_GPIO_EXTI_CLEAR_IT(PPS_PIN);
psdkStat = Osal_GetTimeMs(&timeMs);
if (psdkStat == UAV_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
s_ppsNewestTriggerLocalTimeMs = timeMs;
}
}
  1. Retrieve the local time of the payload device when the PPS signal is triggered Developers need to implement the function to retrieve the local time of the payload device when the PPS signal is triggered and register this function to the specified interface. When the payload device receives the rising edge of the PPS signal, the control program of the payload device developed based on PSDK will record the local time of the payload device when the PPS signal is triggered.
T_UAVReturnCode UAV_Test_GetNewestPpsTriggerLocalTimeUs(uint64_t *localTimeUs)
{
if (localTimeUs == NULL) {
USER_LOG_ERROR("input pointer is null.");
return UAV_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}

if (s_ppsNewestTriggerLocalTimeMs == 0) {
USER_LOG_WARN("pps have not been triggered.");
return UAV_ERROR_SYSTEM_MODULE_CODE_BUSY;
}

*localTimeUs = (uint64_t) (s_ppsNewestTriggerLocalTimeMs * 1000);

return 0;
}
  1. Register the function to retrieve the local time of the payload device when the PPS signal is triggered After registering the function to retrieve the local time of the payload device when the PPS signal is triggered, it is necessary to register this function in the payload device control program. When the payload device receives the rising edge of the PPS signal, the control program of the payload device developed based on PSDK will be able to record the local time of the payload device when the PPS signal is triggered.
// users must register getNewestPpsTriggerTime callback function
uavStat = UAV_TimeSync_RegGetNewestPpsTriggerTimeCallback(s_timeSyncHandler.GetNewestPpsTriggerLocalTimeUs);
if (uavStat != UAV_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("register GetNewestPpsTriggerLocalTimeUsCallback error.");
return uavStat;
}

3. Time Synchronization

The control program of the payload device developed using PSDK retrieves the local time on the payload device through GetTimeMs and converts the local time of the payload device into aircraft time.

  • Retrieve the local time of the payload device
uavStat = GetTimeMs(&currentTimeMs);
if (uavStat != UAV_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("get current time error: 0x%08llX.", uavStat);
continue;
}

uavStat = GetTimeUs(&currentTimeMs);
if (uavStat != UAV_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("get current time error: 0x%08llX.", uavStat);
continue;
}
  • Time Conversion Convert the local time of the payload device to aircraft time.
uavStat = UAV_TimeSync_TransferToAircraftTime(currentTimeUs, &aircraftTime);
if (uavStat != UAV_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("transfer to aircraft time error: 0x%08llX.", uavStat);
continue;
}

USER_LOG_DEBUG("current aircraft time is %d.%d.%d %d:%d %d %d.", aircraftTime.year, aircraftTime.month, aircraftTime.day, aircraftTime.hour, aircraftTime.minute, aircraftTime.second, aircraftTime.microsecond);