ArduPilot开源代码之AP_DAL研读系列

ArduPilot开源代码之AP_DAL研读系列

1. 源由

AP_DAL作为NavEKF3_core的成员变量,在深入研读NavEKF3_core之前,有必要先明确或者搞清楚该类的作用。

首先,What does DAL in AP_DAL mean?

从字面意思分析,感觉像是API接口封装。主要涉及以下传感器对外的统一接口:

AP_DAL整合上述设备对象,做一个整合后,统一对外提供API服务,或者说为NavEKF3_core提供服务。

2. 框架设计

AP_DAL 类通过枚举类型、成员变量和方法提供了对飞行控制数据抽象的封装和管理。它允许记录不同类型的事件和传感器数据,管理不同类型的传感器对象,并提供了单例访问方式以及消息处理的接口。这种设计有助于保持代码的结构化和可维护性,同时提供了对底层硬件和传感器的抽象接口。

2.1 枚举类型

  1. FrameType

    • 枚举了不同的帧类型,用于标识不同的操作或日志记录。具体的枚举值包括 InitialiseFilterEKF2UpdateFilterEKF2InitialiseFilterEKF3UpdateFilterEKF3LogWriteEKF2LogWriteEKF3
  2. Event

    • 定义了各种事件,每个事件用一个唯一的枚举值来标识。例如 resetGyroBiasresetHeightDatumsetTerrainHgtStable 等等。
  3. VehicleClass

    • 标识了不同的车辆类别,包括 UNKNOWNGROUNDCOPTERFIXED_WINGSUBMARINE
  4. StateMask

    • 定义了一个状态掩码,目前只包含 ARMED
  5. EKFType

    • 用于标识不同的扩展卡尔曼滤波器(EKF)类型,包括 EKF2EKF3

2.2 成员变量

  • 静态指针 _singleton:用于保存类的单例实例。
  • 日志和传感器结构体:包括 _RFRH_RFRF_RFRN 等,用于存储不同类型的日志数据或传感器信息。
  • 各种传感器对象:包括 _ins_baro_gps_compass 等,用于访问与传感器相关的功能。

2.3 方法

  • 构造函数和单例获取方法:构造函数初始化对象,单例方法 get_singleton() 用于获取类的唯一实例。
  • 日志记录方法:包括 log_event2log_SetOriginLLH2log_event3 等,用于记录不同类型的事件或传感器数据。
  • 状态获取方法:包括 get_armedget_ekf_typeget_vehicle_class 等,用于获取状态或配置信息。
  • 消息处理方法:一系列的 handle_message 方法,用于处理不同类型的传感器数据或日志消息。

2.4 其他特性

  • 条件编译:在一些方法中使用了条件编译,根据编译器定义的配置选择不同的实现或参数。

3. 设备实例

3.1 IMU

3.1.1 ins

    AP_DAL_InertialSensor &ins() {
   
    return _ins; }

3.1.2 handle_message

    void handle_message(const log_RISH &msg) {
   
   
        _ins.handle_message(msg);
    }
    void handle_message(const log_RISI &msg) {
   
   
        _ins.handle_message(msg);
    }

3.2 气压计

3.2.1 baro

    AP_DAL_Baro &baro() {
   
    return _baro; }

3.2.2 handle_message

    void handle_message(const log_RBRH &msg) {
   
   
        _baro.handle_message(msg);
    }
    void handle_message(const log_RBRI &msg) {
   
   
        _baro.handle_message(msg);
    }

3.3 磁力计

3.3.1 compass

    AP_DAL_Compass &compass() {
   
    return _compass; }

3.3.2 handle_message

    void handle_message(const log_RMGH &msg) {
   
   
        _compass.handle_message(msg);
    }
    void handle_message(const log_RMGI &msg) {
   
   
        _compass.handle_message(msg);
    }

3.4 GPS

3.4.1 gps

    AP_DAL_GPS &gps() {
   
    return _gps; }

3.4.2 handle_message

    void handle_message(const log_RGPH &msg) {
   
   
        _gps.handle_message(msg);
    }
    void handle_message(const log_RGPI &msg) {
   
   
        _gps.handle_message(msg);
    }
    void handle_message(const log_RGPJ &msg) {
   
   
        _gps.handle_message(msg);
    }

3.5 测距仪

3.5.1 rangefinder

#if AP_RANGEFINDER_ENABLED
    AP_DAL_RangeFinder *rangefinder() {
   
   
        return _rangefinder;
    }
#endif

3.5.2 handle_message

    void handle_message(const log_RRNH &msg) {
   
   
#if AP_RANGEFINDER_ENABLED
        if (_rangefinder == nullptr) {
   
   
            _rangefinder = NEW_NOTHROW AP_DAL_RangeFinder;
        }
        _rangefinder->handle_message(msg);
#endif
    }
    void handle_message(const log_RRNI &msg) {
   
   
#if AP_RANGEFINDER_ENABLED
        if (_rangefinder == nullptr) {
   
   
            _rangefinder = NEW_NOTHROW AP_DAL_RangeFinder;
        }
        _rangefinder->handle_message(msg);
#endif
    }

3.6 空速计

3.6.1 airspeed

    AP_DAL_Airspeed *airspeed() {
   
   
        return _airspeed;
    }

3.6.2 handle_message

    void handle_message(const log_RASH &msg) {
   
   
        if (_airspeed == nullptr) {
   
   
            _airspeed = NEW_NOTHROW AP_DAL_Airspeed;
        }
        _airspeed->handle_message(msg);
    }
    void handle_message(const log_RASI &msg) {
   
   
        if (_airspeed == nullptr) {
   
   
            _airspeed = NEW_NOTHROW AP_DAL_Airspeed;
        }
        _airspeed->handle_message(msg);
    }

3.6.3 airspeed_sensor_enabled

获取空速计传感使能状态

    // random methods that AP_NavEKF3 wants to call on AHRS:
    bool airspeed_sensor_enabled(void) const {
   
   
        return _RFRN.ahrs_airspeed_sensor_enabled;
    }

3.7 BeaCon

3.7.1 beacon

#if AP_BEACON_ENABLED
    AP_DAL_Beacon *beacon() {
   
   
        return _beacon;
    }
#endif

3.7.2 handle_message

    void handle_message(const log_RBCH &msg) {
   
   
#if AP_BEACON_ENABLED
        if (_beacon == nullptr) {
   
   
            _beacon = NEW_NOTHROW AP_DAL_Beacon;
        }
        _beacon->handle_message(msg);
#endif
    }
    void handle_message(const log_RBCI &msg) {
   
   
#if AP_BEACON_ENABLED
        if (_beacon == nullptr) {
   
   
            _beacon = NEW_NOTHROW AP_DAL_Beacon;
        }
        _beacon->handle_message(msg);
#endif
    }

3.8 实际里程计

3.8.1 visualodom

#if HAL_VISUALODOM_ENABLED
    AP_DAL_VisualOdom *visualodom() {
   
   
        return _visualodom;
    }
#endif

3.8.2 handle_message

    void handle_message(const log_RVOH &msg) {
   
   
#if HAL_VISUALODOM_ENABLED
        if (_visualodom == nullptr) {
   
   
            _visualodom 
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值