一文读懂 ArduPilot 的前后台架构

背景介绍:
ArduPilot 的 libraries 里大量地使用了“前后台(_frontend、_backend)架构”的代码。
这种架构之所以被大量使用,一个重要原因是:从设计之初就给软件注入了强大的生命力。层次清晰、目的明确、易于维护值得大力推广。然而 ArduPilot 代码量大、复杂度高,很多初学者还没等初窥门径就被迫踏上了从入门到放弃的路途实在可惜。
从本篇起,Sugar 以小马哥的 STM32F103 的遥控器为例,用最简单的代码诠释这个经典架构。希望能助力读者踏上从入门到精通的道路。

初识“铁三角”


代码哪里找?
MultiMCU EDU 公众号后台回复 car 得到这个项目的开源地址。

从软件设计角度看这个架构

1、从应用层往下看
先说一下 Sugar 的认识:libraries 在 ArduPilot 里算是“驱动层”,ArduCopter 等算“设备层”。各种设备根据各自应用需要写功能,故 Sugar 称各种设备层为“应用层”。
以 ArduCopter 为例,如果换个型号的 IMU 就要求重写飞控,这显然是个糟糕的情况。事实上 ArduPilot 能够自动识别接入的传感器硬件,或者通过参数设置就能切换同类型的不同硬件。这就是因为:应用层对应的是前台类(_frontend)的接口。
软件设计上,前台类(_frontend)对应用层负责,专注于满足应用层需求。
2、从任务划分方法看
代码的天性之一就是:每一行代码都对应一个具体的功能。说到这里,Sugar 想到了下面这张图片:

这虽然是个笑话,但 Sugar 估计不少软件开发人员都为此头疼过吧?从软件架构设计上把任务划分清楚,不但符合代码的天性,还能够治愈软件开发者头疼的毛病。
上面说前台类专注于应用层的需求,那么类本身的功能谁来管理呢?答案是:后台类。后台类常见纯虚函数,就是为了统一接口便于管理。那么是统一谁的接口呢?答案是:统一具体干活儿的类的接口。

上代码具体讲这个经典架构

为什么 Sugar 本篇的代码更易懂?答案是:量少、量少、量很少。只写了架构,一点与架构无关的代码都没有。

1、前台类(_frontend)头文件

#ifndef __AP_SHOW__
#define __AP_SHOW__

#include <stdint.h>

#define DISP_MAX_DRIVERS 1

class AP_Show_Backend;

class AP_Show
{
  friend class AP_Show_Backend;
public:
  AP_Show();
  ~AP_Show() {}

  // get singleton
  static AP_Show *get_instance(void) {
    return _instance;
  }

  void init(void);
  void show(uint8_t* str, uint8_t x_pos, uint8_t y_pos);

private:
  static AP_Show *_instance;
  AP_Show_Backend *_drivers[DISP_MAX_DRIVERS];
};

#endif /* __AP_SHOW__ */

Sugar 这个代码是用来执行内容显示的,从应用层角度想,不管用什么显示屏,只要给显示内容下来就行。所以目前只设计两个函数:一个用于初始化的 init(),另一个是用于显示的 show()。
要点汇总:
(1) 后台类(_backend)在前台类(_frontend)中是以前置声明方式出现的,后台类在前台类中定义了指针数组 _drivers;
(2) 为了便于应用层通过类名调用类的对象,定义了前台类的静态指针成员 _instance 和函数 get_instance();
(3) 为了便于后台类(_backend)顺利访问前台类(_frontend)的所有成员,将后台类作为前台类的友元类。
2、前台类(_frontend)源文件

#include <entry.h>
#include "AP_Show.h"
#include "AP_Show_SSD1306_I2C.h"

using namespace rtthread;

AP_Show *AP_Show::_instance;

AP_Show::AP_Show()
{
  _instance = this;
}

void 
AP_Show::init(void)
{
  for(uint8_t i=0; i<DISP_MAX_DRIVERS; i++){
    _drivers[i] = new AP_Show_SSD1306_I2C(*this);
  }
}

void
AP_Show::show(uint8_t* str, uint8_t x_pos, uint8_t y_pos)
{
  for(uint8_t i=0; i<DISP_MAX_DRIVERS; i++){
    _drivers[i]->show(str, x_pos, y_pos);
  }
}

Sugar 在 RT-Thread 操作系统上使用 C++ 的 new 关键字,所以使用 rtthread 命名空间。
要点汇总:
(1) 前台类(_frontend)为后台类(_backend)的指针 new 出干活儿的类;
(2) 前台类调用具体功能是通过后台类(_backend)的指针,后面会看到干活儿的类是后台类的子类。这里涉及一个知识点:父类指针访问子类函数。
3、后台类(_backend)头文件

#ifndef __AP_SHOW_BACKEND__
#define __AP_SHOW_BACKEND__

#include <stdint.h>
#include "AP_Show.h"

class AP_Show_Backend
{
public:
  AP_Show_Backend(AP_Show &show);
  ~AP_Show_Backend() {}
  virtual void show(uint8_t* str, uint8_t x_pos, uint8_t y_pos) = 0;

protected:
  AP_Show &_frontend;
};

#endif /* __AP_SHOW_BACKEND__ */

后台类主要是对功能统一管理,所以会使用纯虚函数。
要点汇总:
(1) 构造函数的形参是前台类(_frontend)的引用;
(2) 在 protected 里通过前台类的引用 _frontend 与前台类保持联系;
(3) 为了让子类能使用 _frontend,把其定义在 protected 里而没有使用 private。
4、后台类(_backend)源文件

#include "AP_Show_Backend.h"

AP_Show_Backend::AP_Show_Backend(AP_Show &show)
: _frontend(show)
{

}

看上去像是在打酱油,然而还是有一个要点:_frontend 是通过构造函数赋值的。
5、干活儿的类头文件

#ifndef __AP_SHOW_SSD1306_I2C__
#define __AP_SHOW_SSD1306_I2C__

#include "AP_Show_Backend.h"

class AP_Show_SSD1306_I2C : public AP_Show_Backend
{
public:
  AP_Show_SSD1306_I2C(AP_Show &show);
  ~AP_Show_SSD1306_I2C() {}

  void show(uint8_t* str, uint8_t x_pos, uint8_t y_pos);

private:
  void _refresh();
};

#endif /* __AP_SHOW_SSD1306_I2C__ */

要点汇总:
(1) 继承于后台类(_backend);
(2) 构造函数里必有前台类的引用;
(3) 继承父类的纯虚函数,自己定义一个干活儿相关的函数 _refresh() 用来刷新屏幕显示。
6、干活儿类源文件

#include "stm32f1xx_hal.h"
#include "ssd1306.h"
#include "AP_Show_SSD1306_I2C.h"

AP_Show_SSD1306_I2C::AP_Show_SSD1306_I2C(AP_Show &show)
: AP_Show_Backend(show)
{
  uint8_t check = SSD1306_Init();
  while(check==0){
    HAL_Delay(1);
  } 
  SSD1306_Fill(SSD1306_COLOR_BLACK);
  _refresh();
}

void
AP_Show_SSD1306_I2C::show(uint8_t* str, uint8_t x_pos, uint8_t y_pos)
{
  SSD1306_GotoXY(x_pos, y_pos);
  SSD1306_Puts((char*) str, &Font_11x18, SSD1306_COLOR_WHITE);
  _refresh();
}

void
AP_Show_SSD1306_I2C::_refresh()
{
  SSD1306_UpdateScreen();
}

要点汇总:
(1) 构造函数通过调用父类的构造函数将前台类的对象传递给父类;
(2) 使用了 "ssd1306.h" 的驱动代码,通过封装好的 HAL 库接口实现显示。这里多说一点,之所以 Sugar 这个代码简单,是因为这里直接对应了硬件驱动,而不是像 ArduPilot 一样在这里对应的是操作系统层的 API。

PS

之所以说本篇内容简单易懂,原因是:
1、Sugar 从设计上回答了“为什么”的问题;
2、代码极简,基本只有架构,每个文件的要点不超过 3 个。

关于 "ssd1306.h" 的使用 Sugar 这里借花献佛来个视频讲解,网上常见的教程就是到这个视频的程度就停止了。本文是在“满足使用要求即可”的基础上说了“如何设计和如何满足设计要求”,吃透本篇内容有利于读者在软件设计的路上过得更顺、更远。欢迎加 Sugar 为好友参加 Sugar 的《软件架构训练计划》与 Sugar 携手共同成长。

本篇为了突出架构没有展示完整代码,Sugar 后续会再推一篇把功能写完,展现一下软件是怎样从设计开始到功能做完的整体过程。

关注作者

欢迎扫码关注我的公众号MultiMCU EDU

提示:在公众号“关于我”页面可加作者微信好友。

喜欢本文求点赞,有打赏我会更有动力。