ArduPilot开源飞控之AP_Baro_DPS310/AP_Baro_DPS280

ArduPilot开源飞控之AP_Baro_DPS310/AP_Baro_DPS280

  • 1. 源由
  • 2. back-end抽象类
  • 3. DPS310/DPS280芯片差异
  • 4. 方法实现
    • 4.1 probe
    • 4.2 init
    • 4.3 update
    • 4.4 timer
  • 5. 参考资料

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驱动层,针对DPS310/DPS280 I2C芯片,进行一个研读和理解。

2. back-end抽象类

AP_Baro_Backend驱动层需实现方法:

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

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

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. DPS310/DPS280芯片差异

DPS310/DPS280的差异主要是修正了芯片温度传感器的一个硬件BUG,相应的寄存器也需要配套进行参数调整。

void AP_Baro_DPS280::set_config_registers(void)
{
    dev->write_register(DPS280_REG_CREG, 0x0C, true); // shift for 16x oversampling
    dev->write_register(DPS280_REG_PCONF, 0x54, true); // 32 Hz, 16x oversample
    dev->write_register(DPS280_REG_TCONF, 0x54 | calibration.temp_source, true); // 32 Hz, 16x oversample
    dev->write_register(DPS280_REG_MCONF, 0x07); // continuous temp and pressure.

    if (is_dps310) {
        // work around broken temperature handling on some sensors
        // using undocumented register writes
        // see https://github.com/infineon/DPS310-Pressure-Sensor/blob/dps310/src/DpsClass.cpp#L442
        dev->write_register(0x0E, 0xA5);
        dev->write_register(0x0F, 0x96);
        dev->write_register(0x62, 0x02);
        dev->write_register(0x0E, 0x00);
        dev->write_register(0x0F, 0x00);
    }
}

因此AP_Baro_DPS310在实现上继承成了AP_Baro_DPS280类。

虽然这个继承的方式并不理想,并未在继承类中发现差异标志,反而在AP_Baro_DPS280类出现了is_dps310成员变量。

建议采用类继承的方式进行方法重写,不过基于历史原因,往往不像书本上的东西。正如大家常说的“理想是丰满的,现实却是骨感的。”

class AP_Baro_DPS310 : public AP_Baro_DPS280 {
    // like DPS280 but workaround for temperature bug
public:
    using AP_Baro_DPS280::AP_Baro_DPS280;
    static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr dev);
};

至于这个GCS软件上面的显示问题,详见:ArduPilot开源飞控之GCS显示DPS310异常问题

  • 【1】DPS310 baro on I2C
  • 【2】Matek h743 Baro DPS310 wrong detcetion

4. 方法实现

4.1 probe

注:从结构化的角度看,本地标识芯片类型可以整合到init代码中。

AP_Baro_DPS280::probe
 │  /********************************************************************************
 │   * device has been initialized, just return imediately                          *
 │   ********************************************************************************/
 ├──> 
 │   └──> return nullptr
 │
 │  /********************************************************************************
 │   * initialize DPS310 or DPS280                                                  *
 │   ********************************************************************************/
 ├──> AP_Baro_DPS280 *sensor = new AP_Baro_DPS280(baro, std::move(_dev))
 │
 │   //本地标识,辨别DPS310/DPS280
 ├──> 
 │   └──> sensor->is_dps310 = _is_dps310
 │
 │   //初始化驱动,内部进行类型设置
 ├──> init(_is_dps310)>
 │   ├──> delete sensor
 │   └──> return nullptr
 └──> return sensor

4.2 init

芯片初始化和数据采集定时器回调注册。

AP_Baro_DPS280::init
 │  /********************************************************************************
 │   * device has been initialized, just return imediately                          *
 │   ********************************************************************************/
 ├──> 
 │   └──> return false;
 │
 │  /********************************************************************************
 │   * chip preliminary check and initialization                                    *
 │   ********************************************************************************/
 ├──> dev->get_semaphore()->take_blocking();
 ├──> bus_type() == AP_HAL::Device::BUS_TYPE_SPI> // setup to allow reads on SPI
 │   └──> dev->set_read_flag(0x80);
 ├──> dev->set_speed(AP_HAL::Device::SPEED_HIGH);
 │
 │  // the DPS310 can get into a state on boot where the whoami is not
 │  // read correctly at startup. Toggling the CS line gets its out of
 │  // this state
 ├──> dev->set_chip_select(true);
 ├──> dev->set_chip_select(false);
 │
 ├──> uint8_t whoami=0;
 ├──> read_registers(DPS280_REG_PID, &whoami, 1) || whoami != DPS280_WHOAMI>
 │   ├──> dev->get_semaphore()->give();
 │   └──> return false;
 ├──> 
 │   ├──> dev->get_semaphore()->give();
 │   └──> return false;
 │
 ├──> dev->setup_checked_registers(4, 20);
 ├──> set_config_registers();
 ├──> instance = _frontend.register_sensor();
 │
 │   // DPS310 or DPS280 type set for GCS software display
 ├──> <_is_dps310>
 │   └──> dev->set_device_type(DEVTYPE_BARO_DPS310);
 ├──> <_is_dps280>
 │   └──> dev->set_device_type(DEVTYPE_BARO_DPS280);
 ├──> set_bus_id(instance, dev->get_bus_id()); 
 ├──> dev->get_semaphore()->give();
 │
 │  /********************************************************************************
 │   * callback for periodic sensor data acquisition                                *
 │   ********************************************************************************/
 │  // request 64Hz update. New data will be available at 32Hz
 ├──> dev->register_periodic_callback((1000 / 64) * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_DPS280::timer, void));
 └──> return true;

4.3 update

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

AP_Baro_DPS280::update
 ├──> 
 │   └──> return
 ├──> WITH_SEMAPHORE(_sem)
 ├──> _copy_to_frontend(instance, pressure_sum/count, temperature_sum/count)
 ├──> pressure_sum = 0
 ├──> temperature_sum = 0
 └──> count=0

4.4 timer

气压数据采集定时回调函数。

AP_Baro_DPS280::timer
 │  /********************************************************************************
 │   * reset registers after software reset from check_health()                     *
 │   ********************************************************************************/
 ├──> 
 │   ├──> pending_reset = false
 │   ├──> set_config_registers()
 │   └──> return
 │
 │  /********************************************************************************
 │   * get sensor raw data                                                          *
 │   ********************************************************************************/
 ├──> read_registers(DPS280_REG_MCONF, &ready, 1) ||
 │      !(ready & (1U<<4)) ||
 │      !dev->read_registers(DPS280_REG_PRESS, buf, 3) ||
 │      !dev->read_registers(DPS280_REG_TEMP, &buf[3], 3)>
 │      // data not ready
 │   ├──> err_count++
 │   ├──> check_health()
 │   └──> return
 ├──> int32_t press = (buf[2]) + (buf[1]<<8) + (buf[0]<<16)
 ├──> int32_t temp  = (buf[5]) + (buf[4]<<8) + (buf[3]<<16)
 │
 │  /********************************************************************************
 │   * fix sensor raw data                                                          *
 │   ********************************************************************************/
 ├──> fix_config_bits32(press, 24)
 ├──> fix_config_bits32(temp, 24)
 ├──> calculate_PT(temp, press, pressure, temperature)
 ├──> last_temperature = temperature
 │
 │  /********************************************************************************
 │   * data check                                                                   *
 │   ********************************************************************************/
 ├──> 
 │   └──> return
 ├──> check_health()
 ├──> 
 │   └──> err_count = 0
 ├──> WITH_SEMAPHORE(_sem)
 │
 │  /********************************************************************************
 │   * data accumulate                                                              *
 │   ********************************************************************************/
 ├──> pressure_sum += pressure
 ├──> temperature_sum += temperature
 └──> count++

5. 参考资料

【1】ArduPilot开源飞控系统之简单介绍
【2】ArduPilot之开源代码Task介绍
【3】ArduPilot飞控启动&运行过程简介
【4】ArduPilot之开源代码Library&Sketches设计
【5】ArduPilot之开源代码Sensor Drivers设计

你可能感兴趣的:(ArduPilot,开源,Ardupilot)