5.16.1 基本功能介绍
时间同步(time_sync)功能主要用于对齐负载设备与无人机的系统时间。考虑到负载设备上可能需要依托无人机时间精度进行一些特殊的处理,比如精准定位,通过对齐两个系统的时间,从而达到提高精度的目的。
PSDK开发中涉及的时间系统主要有两个,无人机的系统时间和PSDK负载系统时间(本地时间)。无人机系统时间提供了基于GPS时间(可看做是UTC时间)和无人机上电时间,负载设备时间依托与开发的设备能力,通常设备会有一个本地系统的时间记录,如果可联网,系统时间可以进行校准也可以获取UTC时间。但挂载在无人机上的设备,通常没有自主联网能力,负载设备的本地时间就无法自动校准,获取的UTC通常也不准确。此时就可以通过时间同步将负载的系统时间与GPS时间拉齐。
PSDK的接口实际上也是给负载设备赋能提供了“联网”能力,最简单的方式就是通过API获取一下GPS时间,设备端校准系统时间,然后不同时间系统都有了正确的时间。但是时间作为一个相对较为精确的计量单位,不同的设备上可能因为时间晶振的误差等影响,在时间的计量中可能存在误差。涉及到多个设备时,设备间的时间差可能就会越来越大,此时需要对时间进行纠偏,也就是时间同步。
PSDK中提供的时间同步是硬同步,通过硬件连接PPS脉冲信号线,通过定频(1HZ)PPS脉冲来实现时间同步。PPS信号线连接后,飞机端会1HZ频率发送脉冲信号,PSDK设备端要具备识别此脉冲信号的能力,并且在获取到脉冲信号的同时将本地时间转换成飞机的时间,这样PSDK端也是1HZ更新一次飞机时间,就可以有效的将两个系统间的误差消除。需要注意,1HZ的频率更新并不意味着时间同步的精度为1s,是将时间误差控制到了1s内时间滴答可能出现的误差,这个依据运行设备和环境,通常来讲这个误差就相当小了。
5.16.2 主要代码文件
├── test_time_sync.c
└── test_time_sync.h
PSDK lib头文件
dji_time_sync.h
说明:
时间同步功能sample只提供了FreeRTOS也就是STM32上的demo,主要是因为开发中在STM32开发板上的硬中断更为方便,实际上Linux也支持时间同步功能,需要通过Linux实现硬中断,原理是一样,此部分主要结合FreeRTOS sample代码来梳理功能的实现原理。
5.16.3 sample代码实现
功能入口
通过PSDK代码结构已经了解到,Free RTOS PSDK相关初始化代码在application.c中实现,与Linux sample结构基本保持一致。通过宏定义:CONFIG_MODULE_SAMPLE_TIME_SYNC_ON来使能时间同步功能(sample)。
T_DjiTestTimeSyncHandler testTimeSyncHandler = {
.PpsSignalResponseInit = DjiTest_PpsSignalResponseInit,
.GetNewestPpsTriggerLocalTimeUs = DjiTest_GetNewestPpsTriggerLocalTimeUs,
};
if (DjiTest_TimeSyncRegHandler(&testTimeSyncHandler) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("regsiter time sync handler error");
goto out;
}
if (DjiTest_TimeSyncStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("psdk time sync init error");
}
分为时间同步回调注册和时间同步功能sample入口两部分。
回调函数注册
与其他功能模块看到的回调注册不太一样,此回调注册并没有注册到闭源库PSDK lib中,只是简单将相关的回调句柄赋给全局变量:s_timeSyncHandler。
T_DjiReturnCode DjiTest_TimeSyncRegHandler(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;
}
回调函数部分主要是PPS相关的调用,其代码文件:
~/Payload-SDK-master/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/drivers/BSP/pps.*
前面提到的sample基于STM32 FreeRTOS方便实现主要是PPS驱动部分,由上述代码路径也可以查看到此文件放在驱动层。如果是使用Linux,主要差别就是PPS部分的适配,将设备的GPIO引出连接PPS,并设置此引脚的中断来获取本地时间。PSDK sample层以及Lib层改动也就不大了,这也是为什么将此部分使用回调开放接口的主要原因。
-
回调函数:DjiTest_PpsSignalResponseInit
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;
}-
此接口用来初始化PPS脉冲中断。设置PPS脉冲上升沿触发中断,引脚对应与硬件上连接PPS信号线的GPIO口。
-
触发中断时,及时获取本地时间(单位ms)。
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;
}
}
-
-
回调函数:DjiTest_GetNewestPpsTriggerLocalTimeUs
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;
}-
此回调是用于获取本地时间,被PSDK lib调用。
-
回传的本地时间单位是us,PSDK lib内部会对时间做比对。
-
本地时间:s_ppsNewestTriggerLocalTimeMs 的获取是PPS触发中断时获取的时间,只要有中断触发,这个时间就会更新。变量参数意义是最新触发PPS时的本地时间,PPS触发本地时间与飞机时间是存在对应关系的。
-
初始化
/**
* @brief Initialise time synchronization module in blocking mode. User should call this function before all other time
* synchronization operations, just like transferring time.
* @note Max execution time of this function is slightly larger than 2000ms.
* @note This function have to be called in user task, rather than main() function, and after scheduler being started.
* @return Execution result.
*/
T_DjiReturnCode DjiTimeSync_Init(void);
API简介
-
用于初始化时间同步模块,此接口调用不在main函数中调用是针对FreeRTOS平台的说明,并且在任务调度scheduler开启之后,Linux问题不大。
注册获取本地时间回调
/**
* @brief Register callback function used to get the newest timestamp in local time system when PPS rising edge signal
* is detected.
* @details DJI uses the timestamp information to synchronise time of local time system and RTK navigation and
* positioning system.
* @param callback: pointer to the callback function.
* @return Execution result.
*/
T_DjiReturnCode DjiTimeSync_RegGetNewestPpsTriggerTimeCallback(DjiGetNewestPpsTriggerLocalTimeUsCallback callback);
API简介
-
此API用于注册获取外部PPS触发时间的回调注册到PSDK lib中。
参数
-
callback,回调函数句柄,用于获取最新PPS触发时的本地时间,也就是回调注册中的函数:DjiTest_GetNewestPpsTriggerLocalTimeUs
/**
* @brief Prototype of callback function used to get the newest PPS triggered timestamp.
* @warning User can not execute blocking style operations or functions in callback function, because that will block DJI
* root thread, causing problems such as slow system response, payload disconnection or infinite loop.
* @param localTimeUs: pointer to memory space used to store PPS triggered timestamp.
* @return Execution result.
*/
typedef T_DjiReturnCode (*DjiGetNewestPpsTriggerLocalTimeUsCallback)(uint64_t *localTimeUs);
初始化PPS脉冲中断
自己外部实现的PPS信号检测初始化要在时间同步功能中启用。
djiStat = s_timeSyncHandler.PpsSignalResponseInit();
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("pps signal response init error");
return djiStat;
}
创建时间同步任务
准备工作做好之后,启用一个时间同步的线程(任务),以1HZ的频率来转换本地时间,本地时间同步飞机时间的功能就完成了。
if (osalHandler->TaskCreate("user_time_sync_task", DjiTest_TimeSyncTask,
DJI_TEST_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;
}
补充说明
通过前面的讲解与说明,我们已经知道了PPS信号脉冲定频1HZ用于与飞机时间同步,此任务中的1HZ频率时间与PPS脉冲是否有冲突了呢?是否还有必要有使用PPS脉冲来硬同步,直接使用任务中1HZ的控制来转换时间不就可以了吗?
-
任务中的1HZ时间转换频率与PPS的1HZ定频没有直接关系。PSDK端是通过PPS信号来对齐本地时间与飞机时间,也可以通过API看到PSDK lib仅拿了一个最新的PPS触发时的本地时间。任务中的1HZ实际也是一个软件层面的时间转化,使用1HZ或者其他频率都是可以的,并不影响本地时间与飞机时间的转换,而且任务运行过程中的本地时间转换,是已经经过PPS脉冲时间对齐过的。
5.16.4 开发注意事项
-
时间同步是基于无人机GPS时间,需要保证无人机GPS信号良好,或者使用RTK。官方文档说明需要无人机连接RTK,实际时间同步与RTK没有强关联,通过GPS时间就可以完成同步。RTK更多的是在于精准定位功能中对获取位置做更为精准的定位。
-
PPS时间信号线必须稳定连接,且PSDK端可以支持PPS信号上升沿触发中断。
-
在PPS信号触发时间与飞机时间对齐中,为控制时间同步的误差,会有一个PPS触发本地时间的有效性控制,控制本地时间误差在500ms。开发过程中可能比较容易出现“aircraft timestamp package is invalid”的错误提示,主要检查两个地方:
-
PPS信号线稳定连接
-
PPS中断获取的时间与回调注册的获取本地时间GetTimeMs要控制再0 ~ 500ms内。事实上PPS触发时也是使用GetTimeMs,PSDK lib中会再次调用,这样可以控制在运行过程中本地时间误差不能太大。
-
特别注意Linux移植过程中如果出现这个报错,可以将GetTimeMs函数实现修改为从0开始计数,不要使用us数量级的UTC时间戳。改成从0开始计数后,PPS触发时间s_ppsNewestTriggerLocalTimeMs也将是从对应从0开始计数,两者差值不超过500ms即可。
-
-
用Linux开发不能直接使用sample,需要在PPS回调部分结合平台来适配。
评论
0 条评论
请登录写评论。