基于BetaFlight开源代码框架简介的框架设计,逐步分析内部模块功能设计。
MSP是Multiwii Serial Protocol的缩写,截止目前为止有两个版本V1和V2。它是一个远程消息协议,主要用在iNav、MultiWii、 CleanFlight、BetaFlight的飞控上。
MSP协议定义了request-response protocol通信机制。发起request一方被认为是"MSP Master",反馈response的一方被认为是"MSP Slave"。
鉴于V1版本在使用过程发现如下问题:
在此基础上V2版本做了如下调整:
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
通过阅读mspSerialProcessReceivedData代码,我们可以得到报文格式:
+---+---+--------+---------+--------+-------------------------------------------------------------+-------------+
| 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 |
+---+---+--------+---------+--------+------+---------+------------------------------+-------------+
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;
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,请参阅:
仔细分析了下代码,貌似没有太多用处(至少在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
【1】iNavFlight之MSP DJI协议分析
【2】iNavFlight之MSP DJI协议天空端请求报文
【3】iNavFlight之MSP DJI协议飞控端请求应答
【4】通过无线自制串口模块连接SpeedyBee或BetaFlightConfigurator
【5】Multiwii Serial Protocol
【6】Multiwii Serial Protocol (MSP)