timesync - RK3588与PX4飞控高精度时间同步节点
timesync - 时间同步节点
简介
基于 ROS Noetic 的高精度时间同步节点,用于 RK3588 与 PX4 飞控之间的时间同步。
功能
- 1PPS GPIO 捕获:通过 GPIO3_C6 捕获 PX4 输出的 1PPS 信号(纳秒精度)
- MAVLink 通信:通过串口与 PX4 通信,解析 TIMESYNC、IMU 等消息
- IMU 数据发布:发布带精确时间戳的 IMU 数据
- 时间戳对齐:使用 PPS 时间戳标记 IMU 数据
架构
PX4 (STM32H7) ──┬── PPS (1Hz) ──▶ RK3588 GPIO3_C6
│
└── UART ────────▶ /dev/ttyS9
│
▼
timesync_node
├── PpsCapture (GPIO 事件)
├── MavlinkReceiver (串口解析)
├── TimeSynchronizer (offset 计算)
└── ROS Topics (数据发布)
时间同步原理
目标
将 PX4 的 IMU 数据时间戳(PX4 boot 时间)转换为 RK3588 本地时间(CLOCK_MONOTONIC)。
公式
RK3588时间 = PX4时间 + offset
其中:
offset = RK3588_PPS时间 - PX4_PPS时间
流程详解
步骤 1: PPS 捕获与 Offset 计算
PX4 RK3588
│ │
├── PPS 上升沿 │
│ hrt_absolute_time() │
│ = 1000000 us │
│ │
├── TIMESYNC(tc1=1000000) ──────▶│
│ │ GPIO 捕获
│ │ = 1234567890 ns
│ │
│ │ offset = 1234567890 - 1000000000
│ │ = 234567890 ns
步骤 2: IMU 时间戳转换
PX4 发送 RAW_IMU:
│ time_usec = 1000500 us
│
│ RK3588 接收后:
│ px4_boot_ns = 1000500 * 1000
│ rk3588_ns = 1000500000 + 234567890 = 1235067890 ns
│
│ imu.header.stamp = 1235067890 ns
步骤 3: Offset 平滑滤波
// 指数移动平均 (EMA)
if (pps_count < 10) {
offset = (raw_offset + offset) / 2; // α = 0.5 (快速收敛)
} else {
offset = (raw_offset + 9*offset) / 10; // α = 0.1 (稳定跟踪)
}
为什么串口延迟不影响精度?
因为 TIMESYNC 消息中的 tc1 是 PX4 发出 PPS 的时间,而不是消息发送时间:
正确的理解:
tc1 = PX4发出PPS的时刻 (硬件精度)
错误的理解:
tc1 = PX4发送TIMESYNC的时刻 (会受串口延迟影响)
因此即使串口有 1ms 延迟,offset 计算仍然基于同一时刻的 PPS 捕获时间。
硬件连接
| 信号 | PX4 引脚 | RK3588 引脚 | 说明 |
|---|---|---|---|
| PPS | GPIO 输出 | GPIO3_C6 | 1Hz 时间同步脉冲 |
| UART TX | UART TX | UART RX | MAVLink 通信 |
| UART RX | UART RX | UART TX | MAVLink 通信 |
| GND | GND | GND | 共地 |
依赖
系统依赖
# GPIO 库
sudo apt-get install libgpiod-dev
编译
cd ~/ros_ws
catkin build timesync
配置
GPIO 权限配置(首次使用必须)
重要: 必须先配置 GPIO 权限,否则无法捕获 PPS 信号。
详细步骤请参考:GPIO_PERMISSION.md
快速配置:
cd ~/ros_ws/src/timesync/scripts
chmod +x setup_gpio_permissions.sh
./setup_gpio_permissions.sh
# 应用组权限
newgrp gpio
运行
启动节点
roslaunch timesync timesync.launch
参数配置
| 参数 | 默认值 | 说明 |
|---|---|---|
port | /dev/ttyS9 | 串口设备 |
baud_rate | 230400 | 串口波特率 |
use_pps | true | 是否启用 PPS 捕获 |
gpio_chip | /dev/gpiochip3 | GPIO chip 设备 |
gpio_line | 22 | GPIO line 偏移 |
publish_rate | 10.0 | 时间发布频率 (Hz) |
自定义参数
roslaunch timesync timesync.launch \
port:=/dev/ttyUSB0 \
baud_rate:=115200 \
gpio_line:=22
Topics
发布的 Topics
| Topic | 类型 | 频率 | 说明 |
|---|---|---|---|
imu/data | sensor_msgs/Imu | >100 Hz | IMU 数据(带时间同步后的时间戳) |
px4_pps_time | std_msgs/Time | 1 Hz | PX4 的 PPS 时间戳(来自 TIMESYNC) |
sync_offset_us | std_msgs/Int64 | 10 Hz | 平滑后的时间 offset(微秒) |
raw_offset_us | std_msgs/Int64 | 1 Hz | 原始时间 offset(微秒) |
日志输出
正常运行日志
[INFO] PPS: GPIO capture started on /dev/gpiochip3 line 22
[INFO] PPS: Capture thread running, waiting for pulses...
[INFO] MAVLink: Serial port /dev/ttyS9 opened at 230400 baud
[INFO] TimeSync node started
[INFO] PPS capture enabled
[INFO] MAVLink receiver enabled
[INFO] PPS: *** FIRST PULSE CAPTURED ***
[INFO] PPS: Timestamp: 4493.804124494 sec
[INFO] PPS: Pulse # 1 | RISING edge | ts=4493.804124494 | interval=0.000000 sec
[INFO] PPS: Pulse # 2 | RISING edge | ts=4494.804162016 | interval=1.000038 sec
[INFO] MAVLink TIMESYNC: tc1=4197059186 us, ts1=1, local=4198000123456 ns
[INFO] === TimeSync Update ===
[INFO] PX4 PPS (tc1): 4197059186 us
[INFO] Sequence (ts1): 1
[INFO] Raw offset: 123456 us
[INFO] Smoothed offset: 123450 us
[INFO] has_sync: 1
模块说明
PpsCapture
1PPS GPIO 捕获模块,使用 libgpiod 捕获上升沿事件。
头文件: include/timesync/PpsCapture.hpp
主要接口:
class PpsCapture {
public:
PpsCapture(const std::string& chip_device, int line_offset);
bool isActive() const;
uint64_t getLastTimestampNs() const;
void stop();
};
MavlinkReceiver
MAVLink 串口通信和消息解析模块。
头文件: include/timesync/MavlinkReceiver.hpp
主要接口:
class MavlinkReceiver {
public:
MavlinkReceiver(const std::string& port, int baud_rate);
void setImuCallback(ImuCallback callback);
void setTimeSyncCallback(TimeSyncCallback callback);
bool isOpen() const;
};
TimeSyncNode
主节点,协调各模块并发布 ROS Topics。
文件: src/TimeSyncNode.cpp
主要功能:
- 加载配置参数
- 初始化 PpsCapture 和 MavlinkReceiver 模块
- 处理 TIMESYNC 和 IMU 消息
- 发布时间同步后的数据
TimeSynchronizer
时间同步算法模块,计算和维护 RK3588 与 PX4 之间的时间 offset。
头文件: include/timesync/TimeSynchronizer.hpp
主要功能:
- 从 TIMESYNC 消息更新时间 offset
- 使用指数平滑滤波处理 offset
- 将 PX4 boot 时间转换为本地同步时间
- 检测 PX4 重启并重置同步状态
故障排查
PPS 捕获失败
[WARN] PPS: Failed to open GPIO chip /dev/gpiochip3
解决方案: 参考 GPIO_PERMISSION.md
串口打开失败
[ERROR] MAVLink: Failed to open serial port /dev/ttyS9
检查:
# 检查串口设备
ls -l /dev/ttyS*
# 检查用户权限
sudo usermod -a -G dialout $USER
找不到正确的 gpiochip
# 列出所有 gpiochip
gpiodetect
# 查看 GPIO lines
gpioinfo gpiochip0
gpioinfo gpiochip1
...
