Time Synchronization
Overview
Time synchronization is a function for synchronizing the time of the payload and the time of the drone. PSDK synchronizes the time of the payload and the RTK-capable drone through the PPS signal (periodic pulse). The load device with the "time synchronization" function can facilitate users to smoothly use the log to troubleshoot various faults during the flight of the drone, analyze the data sampled by the sensor, and obtain accurate positioning information.
This article refers to
- Drone Time: The time of the drone system.
- Local Time: The time on the load device.
Time Synchronization
After the load device developed using PSDK installed on the drone is powered on, the time synchronization function module will be initialized to eliminate the clock difference between the load device and the drone, and synchronize the time of the load device and the drone.
Note: Before using the time synchronization function, please use the Mobile App to confirm that the drone and RTK satellite maintain a good communication status; the Mobile App can be an APP released by DJI, such as DJI Pilot, or The Mobile App developed based on MSDK is shown in Figure 1. Viewing satellite communication status.
Figure 1. View satellite communication status
- Install the load device on the gimbal of the drone. After the drone is powered on, the load device developed using PSDK will receive the PPS hardware pulse signal sent by the drone;
- When the load device detects the rising edge of the PPS signal, the load device needs to record the local time on the load device;
- The underlying handler of the PSDK will get the time on the UAS that is synchronized with the PPS signal.
Note
- Please ensure that the delay between the rising edge of the PPS signal reaching the load and the load recording the local time is less than 1ms.
- Please use the form of hardware interrupt to realize the response of PPS signal.
- The underlying processing program of PSDK will calculate the clock difference between the local time of the load device and the time of the drone system, so as to realize the synchronization of the time between the load device and the drone system.
- The payload device converts the local time of the payload device to the time on the drone through the
DjiTimeSync_TransferToAircraftTime
interface. - Leap seconds change over time. Developers can choose whether implementing compensation to fix the time gap or not,check the table below for different models.
Model | Clock Source | Compensation Required |
---|---|---|
M300 RTK Gimbal Port | RTK, GPS | Yes, currently 18 seconds ahead |
M300 RTK OSDK Port | APP | No |
M350 RTK Gimbal Port | RTK, GPS | Yes, currently 18 seconds ahead |
M350 RTK E-Port Port | APP | No |
M30/M30T | RTK, GPS | Yes, currently 18 seconds ahead |
Mavic 3E/3T | GPS | No |
Using the time synchronization function
1. Configure PPS pin parameters
In order to enable the PPS pin to receive the PPS signal correctly, it is necessary to set various parameters of the PPS pin, and enable the function of the PPS hardware pin to receive the PPS time synchronization signal.
T_DjiReturnCode DjiTest_PpsSignalResponseInit(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
/* Enable GPIOD clock */
__HAL_RCC_GPIOD_CLK_ENABLE();
/* Configure pin as input floating */
GPIO_InitStructure.Mode = GPIO_MODE_IT_RISING;
GPIO_InitStructure.Pull = GPIO_NOPULL;
GPIO_InitStructure.Pin = PPS_PIN;
HAL_GPIO_Init(PPS_PORT, &GPIO_InitStructure);
/* Enable and set EXTI Line Interrupt to the lowest priority */
HAL_NVIC_SetPriority(PPS_IRQn, PPS_IRQ_PRIO_PRE, PPS_IRQ_PRIO_SUB);
HAL_NVIC_EnableIRQ(PPS_IRQn);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
2. Time synchronization function module initialization
To use the time synchronization function, the time synchronization module needs to be initialized.
djiStat = DjiTimeSync_Init();
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("time synchronization module init error.");
return djiStat;
}
3. Develop and register a function to get the local time on the payload device
When the load device developed based on PSDK uses the time synchronization function, it needs to respond to the PPS time synchronization signal pushed by the drone by means of hardware interruption; when the latest PPS signal is triggered, the load device control program developed based on PSDK needs to obtain the Time local to the load device.
- Develop and register the hardware interrupt handler function The developer needs to implement the hardware interrupt processing function and register the hardware interrupt processing function to the specified interface. When the load device receives the rising edge of the PPS signal, the hardware interrupt processing function can process the PPS time synchronization signal.
void DjiTest_PpsIrqHandler(void)
{
T_DjiReturnCode 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 == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
s_ppsNewestTriggerLocalTimeMs = timeMs;
}
}
- Get the local time of the load device when the PPS signal is triggered The developer needs to implement the function of obtaining the local time on the load device when the PPS signal is triggered, and register the function of this function in the specified interface. When the load device receives the rising edge of the PPS signal, the load device control program developed based on PSDK can record the local time on the load device when the PPS signal is triggered.
T_DjiReturnCode DjiTest_GetNewestPpsTriggerLocalTimeUs(uint64_t *localTimeUs)
{
if (localTimeUs == NULL) {
USER_LOG_ERROR("input pointer is null.");
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
if (s_ppsNewestTriggerLocalTimeMs == 0) {
USER_LOG_WARN("pps have not been triggered.");
return DJI_ERROR_SYSTEM_MODULE_CODE_BUSY;
}
*localTimeUs = (uint64_t) (s_ppsNewestTriggerLocalTimeMs * 1000);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
- Register the function to obtain the local time of the load device when the PPS signal is triggered After registering the function to obtain the local time function of the load device when the PPS signal is triggered, the function needs to be registered in the load device control program. When the load device receives the rising edge of the PPS signal, the load device control program developed based on PSDK can Record the local time of the load device when the PPS signal is triggered.
// users must register getNewestPpsTriggerTime callback function
djiStat = DjiTimeSync_RegGetNewestPpsTriggerTimeCallback(s_timeSyncHandler.GetNewestPpsTriggerLocalTimeUs);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("register GetNewestPpsTriggerLocalTimeUsCallback error.");
return djiStat;
}
4. Time synchronization
The payload device control program developed using PSDK gets the local time on the payload device through PsdkOsal_GetTimeMs
and converts the time on the payload device to the time of the UAS.
- Get the local time of the load device
djiStat = osalHandler->GetTimeMs(¤tTimeMs);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("get current time error: 0x%08llX.", djiStat);
continue;
}
- Time conversion Convert the time local to the payload device to the time on the drone system.
djiStat = DjiTimeSync_TransferToAircraftTime(currentTimeMs * 1000, &aircraftTime);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("transfer to aircraft time error: 0x%08llX.", djiStat);
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);