• iNavFlight之MSP Sensor报文格式


    1. MSP v2传感报文介绍

    鉴于飞控近年来发展历程及趋势

    1. 设计成熟度的提升
    2. 大量传感器的应用
    3. 传感器干扰问题分析
    4. 硬件接口多样化问题
    5. 软件设计复杂度的提高
    6. 配置&使用的简洁化要求

    在传感器应用领域,期望更多的标准化设计,MSPv2协议在拓展v1时,就考虑了这方面的需求。

    1. 硬件接口:Rx/Tx/VCC/GND (UART)
    2. 软件接口:MSP v2协议格式
    3. 报文解析:根据command来表征和区分不同传感器数据

    2. MSP v2协议格式

      +---+---+--------+---------+--------+------+---------+------------------------------+-------------+
      |                            Multiwii Serial Protocol V2                length = 9 + payload size |
      +---+---+--------+---------+--------+------+---------+------------------------------+-------------+
      | $ | X | < ! >  | flag(1) | cmd(2)        | size(2) | payload(16bit len)           | checksum_v2 |
      +---+---+--------+---------+--------+------+---------+------------------------------+-------------+
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • ‘$’:表示SOF(Start Of a frame)
    • ‘X’:表示V2
    • ‘<’: 表示request
    • ‘>’:表示response
    • ‘!’:表示error
    • payload: 传感数据

    这里要注意的一个问题是网络字节序,尤其是对通信比较熟悉的朋友。常规的逻辑是这样的:

    发送端CPU字节序 — Host2Network转换字节序 —> 网络传输(大端字节序) — Network2Host转换字节序 —> 接收端CPU字节序
    上述两个逻辑转换:Host2Network/Network2Host来确保发送和接受CPU能根据本地的存储字节序来解析多字节变量

    【但是】飞控代码上看,串口收到报文以后,直接将buffer一个指针强行变换到定义的结构体上了。

    【好嘛,这么粗暴处理!!!】STM32可是小端字节序的呀,这么大胆??? 猜测这些传感模块大都是小端字节序或者8位单片机,所以整个系统都是小端的,就没有大系统这么复杂了。

    3. MSP v2传感代码流程

    iNav应用代码从main开始进入,根据配置信息使能串口;当串口收到传感器MSP v2传感报文时,将信息送到mspProcessSensorCommand进行解析。

    taskHandleSerial
     └──> mspSerialProcess
         └──> mspFcProcessCommand
             └──> mspProcessSensorCommand
    
    main
     └──> init
         └──> fcTasksInit   //setTaskEnabled(TASK_SERIAL, true);
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8

    4. MSP v2 传感器

    截止发稿日,在MSP v2协议上支持的传感器根据cmd(2),有如下几种:

    src/main/msp/msp_protocol_v2_sensor.h

    #define MSP2_IS_SENSOR_MESSAGE(x)   ((x) >= 0x1F00 && (x) <= 0x1FFF)
    
    #define MSP2_SENSOR_RANGEFINDER     0x1F01
    #define MSP2_SENSOR_OPTIC_FLOW      0x1F02
    #define MSP2_SENSOR_GPS             0x1F03
    #define MSP2_SENSOR_COMPASS         0x1F04
    #define MSP2_SENSOR_BAROMETER       0x1F05
    #define MSP2_SENSOR_AIRSPEED        0x1F06
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8

    4.1 光流传感报文-MSP2_SENSOR_RANGEFINDER

    mspSensorOpflowDataMessage_t

    typedef struct __attribute__((packed)) {
        uint8_t quality;    // [0;255]
        int32_t motionX;
        int32_t motionY;
    } mspSensorOpflowDataMessage_t;
    
    • 1
    • 2
    • 3
    • 4
    • 5

    4.2 测距传感报文-MSP2_SENSOR_OPTIC_FLOW

    mspSensorRangefinderDataMessage_t

    typedef struct __attribute__((packed)) {
        uint8_t quality;    // [0;255]
        int32_t distanceMm; // Negative value for out of range
    } mspSensorRangefinderDataMessage_t;
    
    • 1
    • 2
    • 3
    • 4

    4.3 GPS传感报文-MSP2_SENSOR_GPS

    mspSensorGpsDataMessage_t

    typedef struct __attribute__((packed)) {
        uint8_t  instance;                  // sensor instance number to support multi-sensor setups
        uint16_t gpsWeek;                   // GPS week, 0xFFFF if not available
        uint32_t msTOW;
        uint8_t  fixType;
        uint8_t  satellitesInView;
        uint16_t horizontalPosAccuracy;     // [cm]
        uint16_t verticalPosAccuracy;       // [cm]
        uint16_t horizontalVelAccuracy;     // [cm/s]
        uint16_t hdop;
        int32_t  longitude;
        int32_t  latitude;
        int32_t  mslAltitude;       // cm
        int32_t  nedVelNorth;       // cm/s
        int32_t  nedVelEast;
        int32_t  nedVelDown;
        uint16_t groundCourse;      // deg * 100, 0..36000
        uint16_t trueYaw;           // deg * 100, values of 0..36000 are valid. 65535 = no data available
        uint16_t year;
        uint8_t  month;
        uint8_t  day;
        uint8_t  hour;
        uint8_t  min;
        uint8_t  sec;
    } mspSensorGpsDataMessage_t;
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11
    • 12
    • 13
    • 14
    • 15
    • 16
    • 17
    • 18
    • 19
    • 20
    • 21
    • 22
    • 23
    • 24
    • 25

    4.4 磁力计传感报文-MSP2_SENSOR_COMPASS

    mspSensorCompassDataMessage_t

    typedef struct __attribute__((packed)) {
        uint8_t  instance;
        uint32_t timeMs;
        int16_t  magX; // mGauss, front
        int16_t  magY; // mGauss, right
        int16_t  magZ; // mGauss, down
    } mspSensorCompassDataMessage_t;
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7

    4.5 气压计传感报文-MSP2_SENSOR_BAROMETER

    mspSensorBaroDataMessage_t

    typedef struct __attribute__((packed)) {
        uint8_t  instance;
        uint32_t timeMs;
        float    pressurePa;
        int16_t  temp; // centi-degrees C
    } mspSensorBaroDataMessage_t;
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6

    4.6 空速计传感报文-MSP2_SENSOR_AIRSPEED

    mspSensorAirspeedDataMessage_t

    typedef struct __attribute__((packed)) {
        uint8_t  instance;
        uint32_t timeMs;
        float    diffPressurePa;
        int16_t  temp;              // centi-degrees C
    } mspSensorAirspeedDataMessage_t;
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6

    5. 参考资料

    【1】BetaFlight模块设计之三十二:MSP协议模块分析
    【2】Multiwii Serial Protocol Version 2
    【3】传感模块:MATEKSYS Optical Flow & LIDAR 3901-L0X

  • 相关阅读:
    智能家居——libcurl库简介
    Java IO流与文件(一)
    数据结构简述,时间、空间复杂度,学习网站推荐
    【Linux】部署单机OA项目及搭建spa前后端分离项目
    SpringBoot事务失效场景、事务正确使用姿势
    2023NOIP A层联测25-滈葕
    Flask 进阶
    从趋势到挑战,资深工程师一站式解读:操作系统运维和可观测性
    Python标准库中的typing
    闲鱼的商品结构化是如何演进的
  • 原文地址:https://blog.csdn.net/lida2003/article/details/128034469