class AP_HAL::HAL {
public:
HAL(AP_HAL::UARTDriver* _uartA, // console
AP_HAL::UARTDriver* _uartB, // 1st GPS
AP_HAL::UARTDriver* _uartC, // telem1
AP_HAL::UARTDriver* _uartD, // telem2
AP_HAL::UARTDriver* _uartE, // 2nd GPS
AP_HAL::UARTDriver* _uartF, // extra1
AP_HAL::UARTDriver* _uartG, // extra2
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_UAVCAN
AP_HAL::CANManager* _can_mgr[MAX_NUMBER_OF_CAN_DRIVERS])
#else
AP_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_UAVCAN
if (_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];
}
#endif
AP_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_UAVCAN
AP_HAL::CANManager* can_mgr[MAX_NUMBER_OF_CAN_DRIVERS];
#else
AP_HAL::CANManager** can_mgr;
#endif
};
我们看到ardupilot中有四大系统平台(这里的系统平台指的是基于硬件平台的操作系统和底层驱动的集合,系统平台也可以是虚拟的)实现了该接口类,我们这里分析HAL_ChibiOS
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
)
{}
可以看到,四大系统平台都分别实现了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 unlock
bool lock_port(uint32_t write_key, uint32_t read_key) override;
// control optional features
bool 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 discarded
size_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 writes
bool 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 of
a nbytes packet arrived on the uart. This should be treated as a
time constraint, not an exact time. It is guaranteed that the
packet did not start being received after this time, but it
could have been in a system buffer before the returned time.
This takes account of the baudrate of the link. For transports
that have no baudrate (such as USB) the time estimate may be
less 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 UARTs
static thread_t *uart_thread_ctx;
// table to find UARTDrivers from serial number, used for event handling
static UARTDriver *uart_drivers[UART_MAX_DRIVERS];
// index into uart_drivers table
uint8_t serial_num;
// key for a locked port
uint32_t lock_write_key;
uint32_t lock_read_key;
uint32_t _baudrate;
uint16_t tx_len;
#if HAL_USE_SERIAL == TRUE
SerialConfig sercfg;
#endif
const thread_t* _uart_owner_thd;
struct {
// thread waiting for data
thread_t *thread_ctx;
// number of bytes needed
uint16_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;///< 接收弹性buffer
uint8_t *tx_bounce_buf;///< 发送弹性buffer
ByteBuffer _readbuf{0}; ///< 接收ringbuffer
ByteBuffer _writebuf{0};///< 发送ringbuffer
Semaphore _write_mutex;
const stm32_dma_stream_t* rxdma; ///< 接收dma
const stm32_dma_stream_t* txdma; ///< 发送dma
virtual_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 lock
uint64_t _receive_timestamp[2];
uint8_t _receive_timestamp_idx;
// handling of flow control
enum 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 back
bool 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 *);
};