BetaFlight模块设计之三十二:MSP协议模块分析

BetaFlight模块设计之三十二:MSP协议模块分析

  • 1. MSP协议模块
    • 1.1 MSP描述
    • 1.2 MSP版本优缺点
    • 1.3 MSP代码资源
  • 2. MSP报文解析
    • 2.1 MSP收包状态机
    • 2.2 MSP报文格式
  • 3. MSP报文处理
    • 3.1 MSP请求报文处理(mspSerialProcessReceivedCommand)
    • 3.2 MSP反馈报文处理(mspSerialProcessReceivedReply)
  • 4. 参考资料

基于BetaFlight开源代码框架简介的框架设计,逐步分析内部模块功能设计。

1. MSP协议模块

1.1 MSP描述

MSP是Multiwii Serial Protocol的缩写,截止目前为止有两个版本V1和V2。它是一个远程消息协议,主要用在iNav、MultiWii、 CleanFlight、BetaFlight的飞控上。

MSP协议定义了request-response protocol通信机制。发起request一方被认为是"MSP Master",反馈response的一方被认为是"MSP Slave"。

1.2 MSP版本优缺点

鉴于V1版本在使用过程发现如下问题:

  1. ID支持最大255个,在飞控的发展过程,已经基本用尽。
  2. 消息体最多只有255字节的Payload,对于巨帧(JUMBO frame)来说也是一个限制。
  3. checksum(XOR checksum)不够健壮,不能很好的检测通信错误。

在此基础上V2版本做了如下调整:

  1. 16bit IDs, 兼容IDs 0-255(MSP V1)。
  2. 16bit Payload,扩展了一帧字节数。
  3. checksum(crc8_dvb_s2),相较于XOR算法更加健壮和稳定。

1.3 MSP代码资源

src/main/msp/
├── msp_box.c
├── msp_box.h
├── msp.c
├── msp.h
├── msp_protocol.h
├── msp_protocol_v2_betaflight.h
├── msp_protocol_v2_common.h
├── msp_serial.c
└── msp_serial.h

0 directories, 9 files

2. MSP报文解析

通过阅读mspSerialProcessReceivedData代码,我们可以得到报文格式:

2.1 MSP收包状态机

注:收包状态机,任何一个状态出错回到IDLE(初始态)。
BetaFlight模块设计之三十二:MSP协议模块分析_第1张图片

2.2 MSP报文格式

  +---+---+--------+---------+--------+-------------------------------------------------------------+-------------+
  |                            Multiwii Serial Protocol V1                              length = 6 + payload size |
  +---+---+--------+---------+--------+-------------------------------------------------------------+-------------+
  | $ | M | < or > | size(1) | cmd(1) | payload(0-255)                                              | checksum_v1 |
  +---+---+--------+---------+--------+-------------------------------------------------------------+-------------+

  +---+---+--------+---------+--------+------+---------+---------+--------------------+-------------+-------------+  
  |                            Multiwii Serial Protocol V2 over V1                     length = 12 + payload size |
  +---+---+--------+---------+--------+------+---------+---------+--------------------+-------------+-------------+  
  | $ | M | < or > | size(1) | 255    | flag | cmd(2)  | size(2) | payload(16bit len) | checksum_v2 | checksum_v1 |
  +---+---+--------+---------+--------+------+---------+---------+--------------------+-------------+-------------+  

  +---+---+--------+---------+--------+------+---------+------------------------------+-------------+
  |                            Multiwii Serial Protocol V2                length = 9 + payload size |
  +---+---+--------+---------+--------+------+---------+------------------------------+-------------+
  | $ | X | < or > | flag(1) | cmd(2)        | size(2) | payload(16bit len)           | checksum_v2 |
  +---+---+--------+---------+--------+------+---------+------------------------------+-------------+
  • ‘$’:表示SOF(Start Of a frame)
  • ‘M’:表示V1 or V2 over V1
  • ‘X’:表示V2
  • ‘<’: 表示request
  • ‘>’:表示response
typedef struct __attribute__((packed)) {
    uint8_t size;
    uint8_t cmd;
} mspHeaderV1_t;

typedef struct __attribute__((packed)) {
    uint8_t  flags;
    uint16_t cmd;
    uint16_t size;
} mspHeaderV2_t;

3. MSP报文处理

3.1 MSP请求报文处理(mspSerialProcessReceivedCommand)

mspFcProcessCommand
 ├──> MSP_RESULT_ACK, mspCommonProcessOutCommand
 ├──> MSP_RESULT_ACK, mspProcessOutCommand
 ├──> ret = mspFcProcessOutCommandWithArg
 ├──> MSP_RESULT_ACK, mspFcSetPassthroughCommand  //cmdMSP == MSP_SET_PASSTHROUGH
 ├──> MSP_RESULT_ACK, mspFcDataFlashReadCommand   //cmdMSP == MSP_DATAFLASH_READ
 ├──> ret = mspCommonProcessInCommand
 └──> reply->result = ret;

以上函数是针对MSP协议进行实际ID对应的报文进行处理过程。具体报文ID,请参阅:

  1. msp_protocol.h
  2. msp_protocol_v2_common.h
  3. msp_protocol_v2_betaflight.h

3.2 MSP反馈报文处理(mspSerialProcessReceivedReply)

仔细分析了下代码,貌似没有太多用处(至少在Kakute F7上)。

mspFcProcessReply
void mspFcProcessReply(mspPacket_t *reply)
{
    sbuf_t *src = &reply->buf;
    UNUSED(src); // potentially unused depending on compile options.

    switch (reply->cmd) {
    case MSP_ANALOG:
        {
            uint8_t batteryVoltage = sbufReadU8(src);
            uint16_t mAhDrawn = sbufReadU16(src);
            uint16_t rssi = sbufReadU16(src);
            uint16_t amperage = sbufReadU16(src);

            UNUSED(rssi);
            UNUSED(batteryVoltage);
            UNUSED(amperage);
            UNUSED(mAhDrawn);

#ifdef USE_MSP_CURRENT_METER
            currentMeterMSPSet(amperage, mAhDrawn);
#endif
        }
        break;
    }
}

不过有部分机型还是有这方面的需求的,但是不清楚飞控是从哪里读取电流和毫安时。

./src/main/target/SPRACINGF4EVO/target.h:183:#define USE_MSP_CURRENT_METER
./src/main/target/SPRACINGF3EVO/target.h:157:#define USE_MSP_CURRENT_METER
./src/main/target/SPRACINGF7DUAL/target.h:181:#define USE_MSP_CURRENT_METER
./src/main/target/SPRACINGF3/target.h:189:#define USE_MSP_CURRENT_METER
./src/main/target/NUCLEOF303RE/target.h:137:#define USE_MSP_CURRENT_METER

4. 参考资料

【1】iNavFlight之MSP DJI协议分析
【2】iNavFlight之MSP DJI协议天空端请求报文
【3】iNavFlight之MSP DJI协议飞控端请求应答
【4】通过无线自制串口模块连接SpeedyBee或BetaFlightConfigurator
【5】Multiwii Serial Protocol
【6】Multiwii Serial Protocol (MSP)

你可能感兴趣的:(xFlight,stm32,mcu)