1. class AP_HAL::AP_HAL,该接口类聚合了所有提供给应用层的硬件接口

class AP_HAL::HAL {
public:HAL(AP_HAL::UARTDriver* _uartA, // consoleAP_HAL::UARTDriver* _uartB, // 1st GPSAP_HAL::UARTDriver* _uartC, // telem1AP_HAL::UARTDriver* _uartD, // telem2AP_HAL::UARTDriver* _uartE, // 2nd GPSAP_HAL::UARTDriver* _uartF, // extra1AP_HAL::UARTDriver* _uartG, // extra2AP_HAL::I2CDeviceManager* _i2c_mgr,AP_HAL::SPIDeviceManager* _spi,AP_HAL::AnalogIn*   _analogin,AP_HAL::Storage*    _storage,AP_HAL::UARTDriver* _console,AP_HAL::GPIO*       _gpio,AP_HAL::RCInput*    _rcin,AP_HAL::RCOutput*   _rcout,AP_HAL::Scheduler*  _scheduler,AP_HAL::Util*       _util,AP_HAL::OpticalFlow *_opticalflow,AP_HAL::Flash *_flash,
#if HAL_WITH_UAVCANAP_HAL::CANManager* _can_mgr[MAX_NUMBER_OF_CAN_DRIVERS])
#elseAP_HAL::CANManager** _can_mgr)
#endif:uartA(_uartA),uartB(_uartB),uartC(_uartC),uartD(_uartD),uartE(_uartE),uartF(_uartF),uartG(_uartG),i2c_mgr(_i2c_mgr),spi(_spi),analogin(_analogin),storage(_storage),console(_console),gpio(_gpio),rcin(_rcin),rcout(_rcout),scheduler(_scheduler),util(_util),opticalflow(_opticalflow),flash(_flash){
#if HAL_WITH_UAVCANif (_can_mgr == nullptr) {for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++)can_mgr[i] = nullptr;} else {for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++)can_mgr[i] = _can_mgr[i];}
#endifAP_HAL::init();}struct Callbacks {virtual void setup() = 0;virtual void loop() = 0;};struct FunCallbacks : public Callbacks {FunCallbacks(void (*setup_fun)(void), void (*loop_fun)(void));void setup() override { _setup(); }void loop() override { _loop(); }private:void (*_setup)(void);void (*_loop)(void);};virtual void run(int argc, char * const argv[], Callbacks* callbacks) const = 0;AP_HAL::UARTDriver* uartA;AP_HAL::UARTDriver* uartB;AP_HAL::UARTDriver* uartC;AP_HAL::UARTDriver* uartD;AP_HAL::UARTDriver* uartE;AP_HAL::UARTDriver* uartF;AP_HAL::UARTDriver* uartG;AP_HAL::I2CDeviceManager* i2c_mgr;AP_HAL::SPIDeviceManager* spi;AP_HAL::AnalogIn*   analogin;AP_HAL::Storage*    storage;AP_HAL::UARTDriver* console;AP_HAL::GPIO*       gpio;AP_HAL::RCInput*    rcin;AP_HAL::RCOutput*   rcout;AP_HAL::Scheduler*  scheduler;AP_HAL::Util        *util;AP_HAL::OpticalFlow *opticalflow;AP_HAL::Flash       *flash;
#if HAL_WITH_UAVCANAP_HAL::CANManager* can_mgr[MAX_NUMBER_OF_CAN_DRIVERS];
#elseAP_HAL::CANManager** can_mgr;
#endif
};

继承关系

我们看到ardupilot中有四大系统平台(这里的系统平台指的是基于硬件平台的操作系统和底层驱动的集合,系统平台也可以是虚拟的)实现了该接口类,我们这里分析HAL_ChibiOS

2. class HAL_ChibiOS 实现了AP_HAL::HAL接口类

class HAL_ChibiOS : public AP_HAL::HAL {
public:HAL_ChibiOS();void run(int argc, char* const* argv, Callbacks* callbacks) const override;
};
在实现文件中我们看到:
static HAL_UARTA_DRIVER; ///< #define HAL_UARTA_DRIVER ChibiOS::UARTDriver uartADriver(0)
static HAL_UARTB_DRIVER; ///< #define HAL_UARTB_DRIVER ChibiOS::UARTDriver uartBDriver(1)
static HAL_UARTC_DRIVER; ///< #define HAL_UARTC_DRIVER ChibiOS::UARTDriver uartCDriver(2)
static HAL_UARTD_DRIVER; ///< #define HAL_UARTD_DRIVER ChibiOS::UARTDriver uartDDriver(3)
static HAL_UARTE_DRIVER; ///< #define HAL_UARTE_DRIVER ChibiOS::UARTDriver uartEDriver(4)
static HAL_UARTF_DRIVER; ///< #define HAL_UARTF_DRIVER ChibiOS::UARTDriver uartFDriver(5)
static HAL_UARTG_DRIVER; ///< #define HAL_UARTG_DRIVER Empty::UARTDriver uartGDriver
///< 前面这些宏定义在build/fmuv2/hwdef.h头文件中, 该头文件在编译时由python脚本从hwdef.dat文件中解析然后生成
///< 我们这里的硬件平台的硬件定义文件位于:ardupilot/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat
static ChibiOS::I2CDeviceManager i2cDeviceManager;
static ChibiOS::SPIDeviceManager spiDeviceManager;
static ChibiOS::AnalogIn analogIn;
static ChibiOS::Storage storageDriver;
static ChibiOS::GPIO gpioDriver;
static ChibiOS::RCInput rcinDriver;
static ChibiOS::RCOutput rcoutDriver;
static ChibiOS::Scheduler schedulerInstance;
static ChibiOS::Util utilInstance;
static Empty::OpticalFlow opticalFlowDriver;
static ChibiOS::Flash flashDriver;

在构造函数中,这些对象会被传递进去:

HAL_ChibiOS::HAL_ChibiOS() :AP_HAL::HAL(&uartADriver,&uartBDriver,&uartCDriver,&uartDDriver,&uartEDriver,&uartFDriver,&uartGDriver,&i2cDeviceManager,&spiDeviceManager,&analogIn,&storageDriver,&uartADriver,&gpioDriver,&rcinDriver,&rcoutDriver,&schedulerInstance,&utilInstance,&opticalFlowDriver,&flashDriver,nullptr)
{}

3. 我们进入到具体的uartADriver实例对应的类ChibiOS::UARTDriver中,其属于AP_HAL::UARTDriver接口的实现


可以看到,四大系统平台都分别实现了AP_HAL::UARTDriver接口

class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { ///<
public:UARTDriver(uint8_t serial_num);void begin(uint32_t b) override;void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;void end() override;void flush() override;bool is_initialized() override;void set_blocking_writes(bool blocking) override;bool tx_pending() override;uint32_t available() override;uint32_t txspace() override;int16_t read() override;int16_t read_locked(uint32_t key) override;void _timer_tick(void) override;size_t write(uint8_t c) override;size_t write(const uint8_t *buffer, size_t size) override;// lock a port for exclusive use. Use a key of 0 to unlockbool lock_port(uint32_t write_key, uint32_t read_key) override;// control optional featuresbool set_options(uint8_t options) override;// write to a locked port. If port is locked and key is not correct then 0 is returned// and write is discardedsize_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) override;struct SerialDef {BaseSequentialStream* serial;bool is_usb;bool dma_rx;uint8_t dma_rx_stream_id;uint32_t dma_rx_channel_id;bool dma_tx;uint8_t dma_tx_stream_id;uint32_t dma_tx_channel_id; ioline_t rts_line;int8_t rxinv_gpio;uint8_t rxinv_polarity;int8_t txinv_gpio;uint8_t txinv_polarity;uint8_t get_index(void) const {return uint8_t(this - &_serial_tab[0]);}};bool wait_timeout(uint16_t n, uint32_t timeout_ms) override;void set_flow_control(enum flow_control flow_control) override;enum flow_control get_flow_control(void) override { return _flow_control; }// allow for low latency writesbool set_unbuffered_writes(bool on) override;void configure_parity(uint8_t v) override;void set_stop_bits(int n) override;/*return timestamp estimate in microseconds for when the start ofa nbytes packet arrived on the uart. This should be treated as atime constraint, not an exact time. It is guaranteed that thepacket did not start being received after this time, but itcould have been in a system buffer before the returned time.This takes account of the baudrate of the link. For transportsthat have no baudrate (such as USB) the time estimate may beless accurate.A return value of zero means the HAL does not support this API*/uint64_t receive_time_constraint_us(uint16_t nbytes) override;uint32_t bw_in_kilobytes_per_second() const override {if (sdef.is_usb) {return 200;}return _baudrate/(9*1024);}private:bool tx_bounce_buf_ready;const SerialDef &sdef;// thread used for all UARTsstatic thread_t *uart_thread_ctx;// table to find UARTDrivers from serial number, used for event handlingstatic UARTDriver *uart_drivers[UART_MAX_DRIVERS];// index into uart_drivers tableuint8_t serial_num;// key for a locked portuint32_t lock_write_key;uint32_t lock_read_key;uint32_t _baudrate;uint16_t tx_len;
#if HAL_USE_SERIAL == TRUESerialConfig sercfg;
#endifconst thread_t* _uart_owner_thd;struct {// thread waiting for datathread_t *thread_ctx;// number of bytes neededuint16_t n;} _wait;// we use in-task ring buffers to reduce the system call cost// of ::read() and ::write() in the main loop,使用ringbuffer降低mainloop中read/write系统调用开销uint8_t *rx_bounce_buf;///< 接收弹性bufferuint8_t *tx_bounce_buf;///< 发送弹性bufferByteBuffer _readbuf{0}; ///< 接收ringbufferByteBuffer _writebuf{0};///< 发送ringbufferSemaphore _write_mutex;const stm32_dma_stream_t* rxdma; ///< 接收dmaconst stm32_dma_stream_t* txdma; ///< 发送dmavirtual_timer_t tx_timeout;    bool _in_timer;bool _blocking_writes;bool _initialised;bool _device_initialised;bool _lock_rx_in_timer_tick = false;Shared_DMA *dma_handle;static const SerialDef _serial_tab[];// timestamp for receiving data on the UART, avoiding a lockuint64_t _receive_timestamp[2];uint8_t _receive_timestamp_idx;// handling of flow controlenum flow_control _flow_control = FLOW_CONTROL_DISABLE;bool _rts_is_active;uint32_t _last_write_completed_us;uint32_t _first_write_started_us;uint32_t _total_written;// we remember cr2 and cr2 options from set_options to apply on sdStart()uint32_t _cr3_options;uint32_t _cr2_options;// half duplex control. After writing we throw away bytes for 4 byte widths to// prevent reading our own bytes backbool half_duplex;uint32_t hd_read_delay_us;uint32_t hd_write_us;void half_duplex_setup_delay(uint16_t len);// set to true for unbuffered writes (low latency writes)bool unbuffered_writes;static void rx_irq_cb(void* sd);static void rxbuff_full_irq(void* self, uint32_t flags);static void tx_complete(void* self, uint32_t flags);static void handle_tx_timeout(void *arg);void dma_tx_allocate(Shared_DMA *ctx);void dma_tx_deallocate(Shared_DMA *ctx);void update_rts_line(void);void check_dma_tx_completion(void);void write_pending_bytes_DMA(uint32_t n);void write_pending_bytes_NODMA(uint32_t n);void write_pending_bytes(void);void receive_timestamp_update(void);void thread_init();static void uart_thread(void *);
};

QA1.

  1. 首先,HAL_ChibiOS 是 AP_HAL::HAL这个抽象类的 以ChibiOS为具体操作系统的派生类,所以按照C++惯例,子类构造函数中显式调用基类构造函数即AP_HAL::HAL();
  2. HAL_ChibiOS 相当于已经落实到了具象的操作系统软件硬件平台,比如uartA,他提供具体的:

static HAL_UARTA_DRIVER;

而宏在具体的硬件定义比如fmuv2/ArduPilot_743头文件hwdef.h中:

#define HAL_UARTA_DRIVER ChibiOS::UARTDriver uartADriver(0)

替换完成就是:

ChibiOS::UARTDriver uartADriver(0)

也就是使用ChibiOS领域(namespace)内的UARTDriver 实例化一个对象 uartADriver 并将其地址传入到AP_HAL::HAL基类构造函数中,利用多态特性完成抽象到具体的特化,因为具体的业务逻辑比如ArduCopter或APMrover等凡是在涉及具体软硬件平台方面的操作都是面向接口编程的

故而可以总结业务逻辑层:               ArduCopter ... APMrover\       |         / -----AP_HAL 层---||----------------------------------/                |                 \软硬件平台层:ChibiOS+fmuv2 ...ChibiOS+fmuv5... linux+树莓派等

AP_HAL 分析, 以pixhawk-fmuv2为硬件平台,ChibiOS为底层操作系统:相关推荐

  1. 用反汇编分析c++RVO开启和关闭时的底层原理以及C++prvalue,xvalue和lvalue的相关知识

    用反汇编分析c++RVO开启和关闭时的底层原理以及C++prvalue,xvalue和lvalue的相关知识 前言 三五法则 未开启RVO优化与xvalue和prvalue的关系 测试代码 反汇编配合 ...

  2. 基于pixhawk2.4.6硬件和ChibiOS系统的ardupilot启动流程:从上电到ArduCopter应用层代码

    NOTE: 以 ->>> 开头的为加入的分析和注解 <<<- 链接脚本common.ld ./libraries/AP_HAL_ChibiOS/hwdef/comm ...

  3. 微信硬件平台的基础接入和硬件云标准接入分析

    本文分析基于微信硬件平台的物联网架构,将从物联网的核心要素.物联网的关键场景.微信硬件平台的通信协议分析三个维度去分析.更多的微信硬件平台开发的深度技术原创分享请订阅微信公众号:嵌入式企鹅圈. 微信硬 ...

  4. pixhawk博客导读

    写的东西有点多,写的也有点乱,看题目也不知道内容是什么,为了方便网友观看自己感兴趣的地方,笔者把pixhawk博客归类一下. (由于笔者也是边学习边写的,难免有错误,还请多包涵,提出指正) 1.想学习 ...

  5. 深入解析物联网操作系统(架构/功能/实例分析)

    深入解析物联网操作系统(架构/功能/实例分析)  物联网的主要特点 i. 连接 所谓连接,指的是各种各样的终端设备,都能够通过某种网络技术,连接到一个统一的网络上.任何终端之间都可以相互访问.下一 ...

  6. IOT(29)---深入解析物联网操作系统(架构/功能/实例分析)

    深入解析物联网操作系统(架构/功能/实例分析)  1.       物联网的主要特点 i.             连接 所谓连接,指的是各种各样的终端设备,都能够通过某种网络技术,连接到一个统一 ...

  7. BSP板机支持包、linux启动分析、ARM裸机编程

    文章目录 一.BSP 二.驱动 驱动的基本要素 三.启动分析 1.uboot 2.uboot的作用 3.uboot相关命令 关键的内容: 1)bootargs,启动参数 2)启动命令 3)修改启动延时 ...

  8. WDM内核驱动程序模型分析

    WDM内核驱动程序模型分析  WDM驱动程序是Windows 2000操作系统重要的组成部分,它的正常工作需要有Windows 2000其它内核组件的支持,同时大部分的内核组件也必须同WDM驱动程序交 ...

  9. 鸿蒙轻内核源码分析:文件系统LittleFS

    摘要:本文先介绍下LFS文件系统结构体的结构体和全局变量,然后分析下LFS文件操作接口. 本文分享自华为云社区<# 鸿蒙轻内核M核源码分析系列二一 02 文件系统LittleFS>,作者: ...

最新文章

  1. SQL备份与恢复之备份类型和选项
  2. 商业领袖摘下帽子才能炼成极致
  3. HDU ACM 1065 I Think I Need a Houseboat
  4. [FAQ]VC读取数据源列表和驱动程序列表
  5. js 获取某iframe中document,浏览器兼容
  6. 爬虫实战学习笔记_3 网络请求urllib模块:设置IP代理+处理请求异常+解析URL+解码+编码+组合URL+URL连接
  7. java 配置嵌套事务_Spring 事务嵌套的配置
  8. 解析得了数学,写得了诗书,这是个有趣的灵魂
  9. python3 生成器
  10. dalvik on J2EE: running tomcat on dalvik
  11. LINQ 之 JOIN(2)
  12. 软硬件全开源,航芯方案分享 | 热敏打印机方案
  13. 海康录制视频文件无法播放以及FFmpeg最新版下载
  14. 【Altium Designer 19使用教程】Part2 原理图的绘制
  15. 实时语音视频通话SDK如何实现立体声(二)
  16. EC智能电池信息读取
  17. 【读书笔记】分布式下服务可靠性保障
  18. 【量化金融】收益率、对数收益率、年华收益、波动率、夏普比率、索提诺比率、阿尔法和贝塔、最大回撤
  19. 使用javascript制作 滚动字幕及时钟
  20. 产品品牌想正向刷屏 就需做好精致化内容

热门文章

  1. WordPress主题柒比贰v2.9.8 完美无限制版
  2. 【知识卡片】机器学习模型 都需要标准化、归一化吗?什么时候不需要标准化、归一化
  3. Ubuntu下解决Make的:cc1plus: warnings being treated as errors
  4. 网络问题解决—电脑能上网(QQ微信和浏览器一级网页)但浏览器打不开二级网页
  5. 07年博士考题整理合集!
  6. Java笔记(二)(寒假)
  7. 零基础如何学习优达学城的《无人驾驶入门》?
  8. Unity学习笔记:Unity 3D 飞机大战
  9. 相机内参、畸变、外参说明
  10. Django Ninja简单教程