“雲中誰寄錦書來,雁字回時,月滿西樓”。當無人機在空中飛翔時,從APM飛控到飛手之間有幾條看不見的“風箏線”——(1)2.4GHz的遙控;(2)433/915MHz的數傳;(3)5.8GHz的圖傳;(4)osd(on-screen display)。其中遙控是大家最爲熟知的,用於控制飛行和切換模式。數傳說白了是一個披着射頻的皮的無線串口,波特率57600,連接地面站可實時觀測飛行數據和在線調參。圖傳是FPV(First Person View)必備,傳輸視頻信號用於航拍。osd是錦上添花的部件,將飛行數據疊加到視頻信號上一起傳回地面接收機。
遙控、圖傳和osd都是很成熟的產品,對於開源用戶來說定製性不強,而數傳可以傳回用戶感興趣的任何數據以及在線調參,實爲居家必備之良品。如果選購與APM適配的3DR數傳,無需任何修改,插上APM即可在地面站(Mission Planner)監測無人機的飛行數據。從功能上看,數傳與下載程序兼具串口功能的USB線別無二致,只是形態上有線無線而已。二者的技術基礎是串口以及基於串口的Mavlink通信,本文主要討論如何使用APM中的串口並進行二次開發。
APM2.8串口概述
串口的英文名是UART,全稱Universal Asynchronous Receiver/Transmitter,即通用異步接收/發送機,只要一對傳輸線(RX-TX)即可實現雙向通信。串口通過USB轉TTL模塊可插在電腦的USB口,在設備管理器上體現爲COM口,是單片機調試和通信的重要接口。
對於APM2.8飛控,其主控芯片爲Atmega2560,有4個串口,分別爲UART0~UART3,在APM中起作用的只是前3個,即UART0、UART1和UART2。UART0接USB,UART1接GPS,UART2接數傳。
APM3.2.1源碼爲適應除APM之外的不同硬件(如PIXHAWK),在硬件抽象層HAL(Hardware Abstraction Layer)提供了通用的外設接口。在HAL.h中可以查看HAL類的聲明,串口方面保留了_uartA~_uartE共5個。
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::I2CDriver* _i2c,
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)
:
uartA(_uartA),
uartB(_uartB),
uartC(_uartC),
uartD(_uartD),
uartE(_uartE),
i2c(_i2c),
spi(_spi),
analogin(_analogin),
storage(_storage),
console(_console),
gpio(_gpio),
rcin(_rcin),
rcout(_rcout),
scheduler(_scheduler),
util(_util)
{}
virtual void init(int argc, char * const argv[]) const = 0;
AP_HAL::UARTDriver* uartA;
AP_HAL::UARTDriver* uartB;
AP_HAL::UARTDriver* uartC;
AP_HAL::UARTDriver* uartD;
AP_HAL::UARTDriver* uartE;
AP_HAL::I2CDriver* i2c;
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;
};
落實到APM2.8飛控板上,從HAL_AVR_APM2_Class.cpp中可以查看串口的對應關係,同樣可以得出只用了前3個,且UART0接USB,UART1接GPS,UART2接數傳。源碼與飛控板,一個底層,一個上層,“默契”地達成了一致。
HAL_AVR_APM2::HAL_AVR_APM2() :
AP_HAL::HAL(
&avrUart0Driver, /* phys UART0 -> uartA */
&avrUart1Driver, /* phys UART1 -> uartB */
&avrUart2Driver, /* phys UART2 -> uartC */
NULL, /* no uartD */
NULL, /* no uartE */
&avrI2CDriver,
&apm2SPIDriver,
&avrAnalogIn,
&avrEEPROMStorage,
&avrUart0Driver,
&avrGPIO,
&apm2RCInput,
&apm2RCOutput,
&avrScheduler,
&avrUtil )
{}
如果大家仔細觀察上面APM2.8的方框圖,可以發現數傳和USB接口都是走的UART0,這是爲何?因爲APM2.8採用了一種MUX複用的方式,使得當數傳與USB同時接上的時候,USB會把數傳屏蔽,即UART0占主導地位。在此祭出硬件原理圖,TS5A23157是一個模擬開關,3DR代表數傳。當USB和數傳同時接上時,模擬開關會將3DR_RX與RX0接上,3DR_TX與TX0接上,即串口0把數傳給屏蔽了。
串口源碼分析
一個串口要發揮作用,首先需要初始化,即配置波特率、設置起始位等操作。對於STM32單片機(用於PIXHAWK),還有串口中斷等配置。APM中的Arduino單片機比較簡單,只需配置好波特率,其餘保持默認即可。
Arduino程序的初始化,一般在setup()函數中。不出所料,串口的初始化也在其中,見ArduCopter.pde的setup()函數,可以看到初始化函數init_ardupilot()。
void setup()
{
cliSerial = hal.console;
// Load the default values of variables listed in var_info[]s
AP_Param::setup_sketch_defaults();
// setup storage layout for copter
StorageManager::set_layout_copter();
init_ardupilot();
// initialise the main loop scheduler
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]));
}
在Visual Studio+VMICRO的環境下,按F12或鼠標右鍵可轉到init_ardupilot()的定義,在system.pde的init_ardupilot()中摘出與uartA有關的代碼以便分析。
hal.uartA->begin(map_baudrate(g.serial0_baud), 512, 128);,
//gcs[0].init(hal.uartA);
hal.uartA->set_blocking_writes(false);
第1行和第3行很好理解,分別是uartA設置波特率(115200)和非阻塞模式,第2行的gcs[0]容易讓人迷惑。gcs的全稱爲Ground Control Station,即地面工作站。再轉到gcs的定義,可發現其數據類型爲GCS_MAVLINK,由此可斷定該行代碼的作用是綁定Mavlink和uartA,將數據以Mavlink協議與地面站通信。爲單獨測試串口收發,可取消uartA與Mavlink的綁定,即註釋掉gcs所在行的代碼。
串口數據收發
初始化搞定之後,就可以進行簡單的串口收發測試——串口助手發數據給飛控,飛控返回原數據。串口的接收一般有2種方式:查詢或中斷。Arduino中的串口中斷函數爲SerialEvent,是一種軟中斷,博主將Arduino nano板中測試通過的串口中斷代碼移植到APM源碼中,發現並不起作用。原因尚不明確,或許 APM板本身並不支持,也可能是博主移植的地方不合適。期待有心人進行嘗試,歡迎留言討論。
爲了推進測試進程,轉向查詢方式。有2種方式:1.在ArduCopter.pde的fast_loop中查詢;2.在UserCode.pde中添加代碼。如果要使用UserCode.pde,需在ArduCopter.pde添加相應的宏,才能將UserCode.pde加入編譯。爲了方便,博主在fast_loop()中添加串口接收查詢代碼:
static void fast_loop()
{
// IMU DCM Algorithm
// --------------------
read_AHRS();
// run low level rate controllers that only require IMU data
attitude_control.rate_controller_run();
#if FRAME_CONFIG == HELI_FRAME
update_heli_control_dynamics();
#endif //HELI_FRAME
// write out the servo PWM values
// ------------------------------
set_servos_4();
// Inertial Nav
// --------------------
read_inertia();
// 串口接收查詢 by--嶽小飛
while (hal.uartA->available())
{
uint8_t data = (uint8_t)hal.uartA->read();
hal.uartA->write(data);
}
// run the attitude controllers
update_flight_mode();
// optical flow
// --------------------
#if OPTFLOW == ENABLED
if(g.optflow_enabled) {
update_optical_flow();
}
#endif // OPTFLOW == ENABLED
}
打開串口,APM飛控會發出一串提示字符,包括版本信息,如“Init ArduCopter V3.2.1”。博主發送“YueXiaoFei”,飛控原樣返回,測試通過。基於這個簡單的收發測試,大家可自定義數據協議,發送和接收感興趣的飛行數據,也可學習基於串口的Mavlink協議。
PS:無人機系列的第5篇至此結束,系列博客也隨之告一段落。就應用方面而言,從入門到編譯,從編譯到調試,博主儘可能地將問題講清楚,所有資料免積分下載,也算是爲開源貢獻自己的一份力吧。博客中可能存在一些小錯誤,也歡迎大家在評論區批評指正。力有不逮,敬請見諒~