PPS Time Synchronization Adaptation from RTOS to Linux (UpXtreme SBC)
I'm currently developing an application for the DJI M300 utilizing the PSDK's time synchronization function. The provided sample code and documentation on the DJI forum are tailored for RTOS environments (specifically, using STM32 HAL libraries for GPIO and interrupt handling). My setup involves an UpXtreme SBC running Linux, which inherently handles hardware interactions (like GPIO and interrupts) differently from an RTOS. This architectural mismatch creates a significant challenge in directly implementing the PPS time synchronization as demonstrated in the RTOS examples.
I am seeking guidance or official examples on how to correctly adapt the PSDK's PPS time synchronization mechanism for a Linux environment. Crucially, I have successfully configured the PPS signal to be detected by the Linux kernel, and it's exposed as /dev/pps1.
Specifically, I need to understand the recommended approach for:
- PPS Signal Detection and Timestamp Acquisition: How to correctly read the kernel-timestamped PPS events from /dev/pps1 (e.g., using open, read, and struct pps_fetch_args from <linux/pps.h>), effectively replacing the direct HAL interrupt handler and Osal_GetTimeMs for capturing the precise PPS trigger time.
- High-Resolution Local Time Acquisition: How to obtain a monotonic, high-resolution timestamp in Linux (e.g., using clock_gettime(CLOCK_MONOTONIC_RAW)) at the precise moment of the PPS signal's rising edge, effectively replacing Osal_GetTimeMs.
- Integration with PSDK Time Synchronization API: How to correctly feed these Linux-acquired PPS trigger timestamps into the existing PSDK functions like DjiTimeSync_RegGetNewestPpsTriggerTimeCallback and DjiTimeSync_TransferToAircraftTime.
Additional context
- Target Drone: DJI Matrice 300 RTK (M300)
- SBC: UpXtreme
- Operating System: Ubuntu 22.04 LTS (Linux kernel 6.8.0-60-generic)
- DJI PSDK Version: V3.9.1-beta.0-build.2090
- PPS Pin Configuration: The PPS signal is wired to GPIO 26 on the UpXtreme SBC, and the Linux kernel successfully exposes it as a PPS device: /dev/pps1. This means the necessary kernel modules (pps_core, ptp drivers if applicable) are loaded and functioning correctly.
I would love to have some help in what directions I should focus.
Thank you in advance.
Agent comment from LIPING.ZHOU in Zendesk ticket #145304:
Dear Developer,
Hello and thank you for reaching out to DJI Innovations
Sorry, currently the time synchronization feature is only available in the RTOS platform sample. You can refer to the code and implement the corresponding functionality for the Linux platform yourself. Below are the relevant documents:https://sdk-forum.dji.net/hc/zh-cn/articles/40813170873241-Linux%E6%97%B6%E9%97%B4%E5%90%8C%E6%AD%A5%E5%8A%9F%E8%83%BDPPS%E4%BF%A1%E5%8F%B7%E6%A3%80%E6%B5%8B%E7%A4%BA%E4%BE%8B
We hope that our solution meets your needs satisfactorily. We appreciate your email and wish you a wonderful day!
Best Regards,
DJI Innovations SDK Technical Support Team
°°°
Hello again,
Thank you for your earlier response and for confirming that time synchronization is currently only officially supported in the RTOS example. As mentioned, I am indeed attempting to adapt the PSDK time synchronization for Linux — and while I’ve made progress, I’m still encountering a blocking issue and would appreciate further guidance from your team.
I tried to implement the code as you suggest, I read all the documentation in [https://developer.dji.com/doc/payload-sdk-tutorial/en/function-set/basic-function/time-syn.html], and the result is the code below (although I understood later that I have to use hardware interruption to handle the PPS signal instead of just reading it from /dev/pps1):
typedef struct {
T_DjiReturnCode (*PpsSignalResponseInit)(void);
T_DjiReturnCode (*GetNewestPpsTriggerLocalTimeUs)(uint64_t *localTimeUs);
} T_DjiTestTimeSyncHandler;
static T_DjiTestTimeSyncHandler s_timeSyncHandler;
static T_DjiTaskHandle s_timeSyncThread;
T_DjiReturnCode GetNewestPpsTriggerLocalTimeUs(uint64_t* localTimeUs)
{
printf("\n\n\nGetting Newest PPS Trigger time \n");
if (!localTimeUs)
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
if (s_ppsNewestTriggerLocalTimeUs == 0)
return DJI_ERROR_SYSTEM_MODULE_CODE_BUSY;
*localTimeUs = s_ppsNewestTriggerLocalTimeUs;
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
void* pps_thread_func(void* arg) {
pps_info_t pps_info;
int ret;
pps_seq_t last_assert_sequence = 0;
while (1) {
ret = time_pps_fetch(pps_handle, PPS_TSFMT_TSPEC, &pps_info, NULL);
if (ret < 0) {
perror("time_pps_fetch");
continue;
}
latest_pps_ts = pps_info.assert_timestamp;
s_ppsNewestTriggerLocalTimeUs =
(uint64_t)latest_pps_ts.tv_sec * 1000000 + latest_pps_ts.tv_nsec / 1000;
printf("Latest PPS trigger time: %ld us\n", s_ppsNewestTriggerLocalTimeUs);
}
return NULL;
}
T_DjiReturnCode PPSTimeSync(void)
{
int fd = open("/dev/pps1", O_RDWR);
if (fd < 0) {
perror("open /dev/ppsX");
return -1;
}
if (time_pps_create(fd, &pps_handle) < 0) {
perror("time_pps_create");
return -1;
}
if (time_pps_getparams(pps_handle, &pps_params) < 0) {
perror("time_pps_getparams");
return -1;
}
pps_params.mode |= PPS_CAPTUREASSERT;
pps_params.mode |= PPS_TSFMT_TSPEC;
if (time_pps_setparams(pps_handle, &pps_params) < 0) {
perror("time_pps_setparams");
return -1;
}
pthread_t thread;
pthread_create(&thread, NULL, pps_thread_func, NULL);
pthread_detach(thread);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
static void *DjiTest_TimeSyncTask(void *arg)
{
T_DjiReturnCode djiStat;
uint32_t currentTimeMs = 0;
T_DjiTimeSyncAircraftTime aircraftTime = {0};
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
uint8_t totalSatelliteNumber = 0;
USER_UTIL_UNUSED(arg);
while (1) {
printf("Sleeping Task 1 second\n");
osalHandler->TaskSleepMs(1000 / DJI_TIME_SYNC_TASK_FREQ);
// djiStat = DjiTest_FcSubscriptionGetTotalSatelliteNumber(&totalSatelliteNumber);
// if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
// USER_LOG_ERROR("get total satellite number error: 0x%08llX.", djiStat);
// continue;
// }
djiStat = osalHandler->GetTimeMs(¤tTimeMs);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("get current time error: 0x%08llX.", djiStat);
continue;
}
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 %04d-%02d-%02d %02d:%02d:%02d %d.",
aircraftTime.year, aircraftTime.month, aircraftTime.day,
aircraftTime.hour, aircraftTime.minute, aircraftTime.second, aircraftTime.microsecond);
}
}
/* Exported functions definition ---------------------------------------------*/
/**
* @brief Register handler function for initialising PPS pin configure and reporting the latest local time when PPS is
* triggered. This function have to be called before calling DjiTest_TimeSyncInit().
* @param timeSyncHandler: pointer to handler function for time synchronization.
* @return Execution result.
*/
T_DjiReturnCode DjiTimeSyncRegHandler(T_DjiTestTimeSyncHandler *timeSyncHandler)
{
if (timeSyncHandler->PpsSignalResponseInit == NULL) {
USER_LOG_ERROR("reg time sync handler PpsSignalResponseInit error");
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
if (timeSyncHandler->GetNewestPpsTriggerLocalTimeUs == NULL) {
USER_LOG_ERROR("reg time sync handler GetNewestPpsTriggerLocalTimeUs error");
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
memcpy(&s_timeSyncHandler, timeSyncHandler, sizeof(T_DjiTestTimeSyncHandler));
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode DjiTimeSyncStartService(void)
{
T_DjiReturnCode djiStat;
osalHandler = DjiPlatform_GetOsalHandler();
djiStat = DjiTimeSync_Init();
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("time synchronization module init error.");
return djiStat;
}
printf("Time sync initialized\n");
if (s_timeSyncHandler.PpsSignalResponseInit == NULL) {
USER_LOG_ERROR("time sync handler PpsSignalResponseInit interface is NULL error");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
printf("PPS signal is not null\n");
if (s_timeSyncHandler.GetNewestPpsTriggerLocalTimeUs == NULL) {
USER_LOG_ERROR("time sync handler GetNewestPpsTriggerLocalTimeUs interface is NULL error");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
printf("Get Newest PPS is not null\n");
// 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;
}
printf("Time Sync Reg Newest PPS Trigger time OK\n");
if (osalHandler->TaskCreate("user_time_sync_task", DjiTest_TimeSyncTask,
DJI_TIME_SYNC_TASK_STACK_SIZE, NULL, &s_timeSyncThread) !=
DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("user time sync task create error.");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
printf("Task Created\n");
djiStat = s_timeSyncHandler.PpsSignalResponseInit();
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("pps signal response init error\n");
return djiStat;
}
printf("PPS signal response OK\n");
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
int main(int argc, char **argv)
{
Application application(argc, argv);
T_DjiReturnCode djiStat;
s_timeSyncHandler = {
.PpsSignalResponseInit = PPSTimeSync,
.GetNewestPpsTriggerLocalTimeUs = GetNewestPpsTriggerLocalTimeUs
};
DjiTimeSyncRegHandler(&s_timeSyncHandler);
T_DjiReturnCode stat = DjiTimeSyncStartService();
}
But every time I run my code I get this error:
[30.580][time_sync]-[Error]-[DjiTimeSync_TransferToAircraftTime:307) Payload have not synchronised time. Please call DjiTimeSync_RegGetNewestPpsTriggerTimeCallback interface to register GetNewestPpsTriggerLocalTimeUsCallback callback function before transferring time, and please check hardware connection / software configure of PPS signal and RTK signal to ensure PPS signal i[30.580][user]-[Error]-[DjiTest_TimeSyncTask:221) transfer to aircraft time error: 0x000000E4.
The problem is that I didn't understand, even reading the code for RTOS, how this GetNewestPpsTriggerLocalTimeUs will be triggered (in my code is never triggered), if this happen automatically when an PPS pulse is identified. So I would appreciate to have some help to understand how this function is triggered (since it's the core of the error that is showed when I run my code), and if I need to do some extra configuration (in Osalhandler, for example) to get this working.