ArduPilot开源飞控之AP_Baro_MSP

ArduPilot开源飞控之AP_Baro_MSP

  • [1. 源由](#1. 源由)
  • [2. back-end抽象类](#2. back-end抽象类)
  • [3. 方法实现](#3. 方法实现)
    • [3.1 AP_Baro_MSP](#3.1 AP_Baro_MSP)
    • [3.2 update](#3.2 update)
    • [3.3 handle_msp](#3.3 handle_msp)
    • [3.4 MSP UART port](#3.4 MSP UART port)
  • [4. 参考资料](#4. 参考资料)

1. 源由

鉴于ArduPilot开源飞控之AP_Baro中涉及Sensor Driver有以下总线类型:

  1. I2C
  2. Serial UART
  3. CAN
  4. SITL //模拟传感器(暂时并列放在这里)

ArduPilot之开源代码Sensor Drivers设计的front-end / back-end分层设计思路,AP_Baro主要描述的是front-end。

为了更好的从整体理解气压计这个传感器的嵌入式应用,这里深入到back-end驱动层,针对基于MSP协议的气压计设备,进行一个研读和理解。

2. back-end抽象类

AP_Baro_Backend驱动层需实现方法:

  • void update()
  • static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)

注:通常来说使用ChibiOS的都有定时器,如果没有定时器,可以使用void accumulate(void)来实现传感器的数据定时获取。

C 复制代码
class AP_Baro_Backend
{
public:
    AP_Baro_Backend(AP_Baro &baro);
    virtual ~AP_Baro_Backend(void) {};

    // each driver must provide an update method to copy accumulated
    // data to the frontend
    virtual void update() = 0;

    // accumulate function. This is used for backends that don't use a
    // timer, and need to be called regularly by the main code to
    // trigger them to read the sensor
    virtual void accumulate(void) {}

    void backend_update(uint8_t instance);

    //  Check that the baro valid by using a mean filter.
    // If the value further that filtrer_range from mean value, it is rejected.
    bool pressure_ok(float press);
    uint32_t get_error_count() const { return _error_count; }

#if AP_BARO_MSP_ENABLED
    virtual void handle_msp(const MSP::msp_baro_data_message_t &pkt) {}
#endif

#if AP_BARO_EXTERNALAHRS_ENABLED
    virtual void handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt) {}
#endif

    /*
      device driver IDs. These are used to fill in the devtype field
      of the device ID, which shows up as BARO_DEVID* parameters to
      users.
     */
    enum DevTypes {
        DEVTYPE_BARO_SITL     = 0x01,
        DEVTYPE_BARO_BMP085   = 0x02,
        DEVTYPE_BARO_BMP280   = 0x03,
        DEVTYPE_BARO_BMP388   = 0x04,
        DEVTYPE_BARO_DPS280   = 0x05,
        DEVTYPE_BARO_DPS310   = 0x06,
        DEVTYPE_BARO_FBM320   = 0x07,
        DEVTYPE_BARO_ICM20789 = 0x08,
        DEVTYPE_BARO_KELLERLD = 0x09,
        DEVTYPE_BARO_LPS2XH   = 0x0A,
        DEVTYPE_BARO_MS5611   = 0x0B,
        DEVTYPE_BARO_SPL06    = 0x0C,
        DEVTYPE_BARO_UAVCAN   = 0x0D,
        DEVTYPE_BARO_MSP      = 0x0E,
        DEVTYPE_BARO_ICP101XX = 0x0F,
        DEVTYPE_BARO_ICP201XX = 0x10,
        DEVTYPE_BARO_MS5607   = 0x11,
        DEVTYPE_BARO_MS5837   = 0x12,
        DEVTYPE_BARO_MS5637   = 0x13,
        DEVTYPE_BARO_BMP390   = 0x14,
    };
    
protected:
    // reference to frontend object
    AP_Baro &_frontend;

    void _copy_to_frontend(uint8_t instance, float pressure, float temperature);

    // semaphore for access to shared frontend data
    HAL_Semaphore _sem;

    virtual void update_healthy_flag(uint8_t instance);

    // mean pressure for range filter
    float _mean_pressure; 
    // number of dropped samples. Not used for now, but can be usable to choose more reliable sensor
    uint32_t _error_count;

    // set bus ID of this instance, for BARO_DEVID parameters
    void set_bus_id(uint8_t instance, uint32_t id) {
        _frontend.sensors[instance].bus_id.set(int32_t(id));
    }
};

3. 方法实现

由于气压数据来自串口,因此,其逻辑相对简单,没有校准等复杂物理公式。

3.1 AP_Baro_MSP

实例初始化。

C 复制代码
AP_Baro_MSP::AP_Baro_MSP
 ├──> msp_instance = _msp_instance;
 ├──> instance = _frontend.register_sensor();
 └──> set_bus_id(instance, AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_MSP,0,msp_instance,0));

3.2 update

front-end / back-end数据更新。

C 复制代码
AP_Baro_MSP::update
 └──> <count>
     ├──> WITH_SEMAPHORE(_sem);
     ├──> _copy_to_frontend(instance, sum_pressure/count, sum_temp/count);
     ├──> sum_pressure = sum_temp = 0;
     └──> count = 0;

3.3 handle_msp

处理MSP协议中气压数据。

C 复制代码
AP_Baro_MSP::handle_msp
 ├──> <pkt.instance != msp_instance> // not for us
 │   └──> return;
 ├──> WITH_SEMAPHORE(_sem);
 ├──> sum_pressure += pkt.pressure_pa;
 ├──> sum_temp += pkt.temp*0.01;
 └──> count++;

typedef struct PACKED {
    uint8_t instance;
    uint32_t time_ms;
    float pressure_pa;
    int16_t temp; // centi-degrees C
} msp_baro_data_message_t;

3.4 MSP UART port

满足MSP协议格式,参考:BetaFlight模块设计之三十二:MSP协议模块分析

C 复制代码
AP_Vehicle::setup
 └──> AP_MSP::init
     └──> AP_MSP::loop  //thread_create
         └──> AP_MSP_Telem_Backend::process_incoming_data
             └──> AP_MSP_Telem_Backend::msp_process_received_command
                 └──> AP_MSP_Telem_Backend::msp_process_command
                     └──> AP_MSP_Telem_Backend::msp_process_sensor_command
                         └──> AP_MSP_Telem_Backend::msp_handle_baro
                             └──> AP_Baro::handle_msp
                                 └──> AP_Baro_MSP::handle_msp

4. 参考资料

【1】ArduPilot开源飞控系统之简单介绍

【2】ArduPilot之开源代码Task介绍

【3】ArduPilot飞控启动&运行过程简介

【4】ArduPilot之开源代码Library&Sketches设计

【5】ArduPilot之开源代码Sensor Drivers设计

相关推荐
张有志_1 小时前
STL容器终极解剖:C++ vector源码级实现指南 | 从内存分配到异常安全的全流程避坑
c语言·c++·算法·开源·visual studio
美股研究社1 小时前
百度智能云AI收入增3倍,2025开源引流打赢生态战
人工智能·百度·开源
星霜旅人3 小时前
开源机器学习框架
人工智能·机器学习·开源
山河已无恙12 小时前
基于 DeepSeek LLM 本地知识库搭建开源方案(AnythingLLM、Cherry、Ragflow、Dify)认知
开源·知识库·deepseek
AI服务老曹13 小时前
运用先进的智能算法和优化模型,进行科学合理调度的智慧园区开源了
运维·人工智能·安全·开源·音视频
gz927cool13 小时前
大模型做导师之开源项目学习(lightRAG)
学习·开源·mfc
Ainnle14 小时前
企业级RAG开源项目分享:Quivr、MaxKB、Dify、FastGPT、RagFlow
人工智能·开源
我们的五年18 小时前
MySQL 架构
数据库·mysql·开源
CCF ODC19 小时前
2025年第一期 | CCF ODC《开源战略动态月报》
开源
從南走到北19 小时前
挪车小程序挪车二维码php+uniapp
微信小程序·小程序·开源·微信公众平台