| 123456789101112131415161718192021222324252627282930313233 |
- /*
- mavlink class for handling OpenDroneID messages
- */
- #pragma once
- #include "transport.h"
- #include "parameters.h"
- /*
- abstraction for MAVLink on a serial port
- */
- class MAVLinkSerial : public Transport { // 继承自 Transport 基类
- public:
- using Transport::Transport;
- MAVLinkSerial(HardwareSerial &serial, mavlink_channel_t chan);
- void init(void) override; // 初始化串口和MAVLink
- void update(void) override; // 主循环调用,处理收发数据
- private:
- HardwareSerial &serial; // 串口对象引用(实际使用的串口,如 Serial1、Serial2)
- mavlink_channel_t chan; // MAVLink 通道号(0、1、2等,用于区分多个MAVLink连接)
- uint32_t last_hb_ms; // 最后一次收到心跳包的时间戳
- uint32_t last_hb_warn_ms; // 最后一次发送心跳警告的时间戳(避免频繁警告)
- uint32_t param_request_last_ms; // 最后一次请求参数的时间
- const Parameters::Param *param_next; // 下一个要发送的参数(用于参数列表传输)
- void update_receive(void); // 接收并处理MAVLink消息
- void update_send(void); // 发送MAVLink消息
- void process_packet(mavlink_status_t &status, mavlink_message_t &msg); // 处理接收到的数据包
- void mav_printf(uint8_t severity, const char *fmt, ...); // 通过MAVLink发送日志/调试信息
- void handle_secure_command(const mavlink_secure_command_t &pkt); // 处理安全命令(加密/签名)
- void arm_status_send(void); // 发送解锁状态
- };
|