ArduPilot之开源代码UARTs and the Console使用

ArduPilot之开源代码UARTs and the Console使用

  • 1. 源由
  • 2. UART定义
    • 2.1 HAL_Empty
    • 2.2 HAL_ChibiOS
    • 2.3 HAL_ESP32
    • 2.4 HAL_Linux
    • 2.5 HAL_SITL
  • 3. 配置参数
    • 3.1 SERIALx_BAUD
    • 3.2 SERIALx_PROTOCOL
    • 3.3 SERIALx_OPTIONS
    • 3.4 SERIAL_PASSx
    • 3.5 SERIAL_PASSTIMO
  • 4. UART常用函数
  • 5. 示例代码
  • 6. 参考资料

1. 源由

ArduPilot的外部传感器主要通过UART/CAN/I2C/SPI等方式接入系统。UART在调试输出、遥测、GPS模块等方面有着诸多应用。了解如何通过HAL与UART对话将有助于理解ArduPilot代码。

2. UART定义

HAL框架设计角度,ArduPilot支持1 + 9个UART端口,其中1个是USB转串口。

libraries/AP_HAL/HAL.cpp

// access serial ports using SERIALn numbering
AP_HAL::UARTDriver* AP_HAL::HAL::serial(uint8_t sernum) const
{
    UARTDriver **uart_array = const_cast(&uartA);
    // this mapping captures the historical use of uartB as SERIAL3
    const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 };
    static_assert(sizeof(mapping) == num_serial, "num_serial must match mapping");
    if (sernum >= num_serial) {
        return nullptr;
    }
    return uart_array[mapping[sernum]];
}

鉴于ArduPilot支持OS版本不同,或多或少有一些差异,UART可能存在不同的配置情况。

2.1 HAL_Empty

空定义,其实现都是空的,类似dummy/stub。后面可以看到有些OS上会有一些空定义的串口。

libraries/AP_HAL_Empty/HAL_Empty_Class.cpp

static UARTDriver uartADriver;
static UARTDriver uartBDriver;
static UARTDriver uartCDriver;

2.2 HAL_ChibiOS

支持10个UART。

libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp

#ifndef HAL_NO_UARTDRIVER
static HAL_UARTA_DRIVER;
static HAL_UARTB_DRIVER;
static HAL_UARTC_DRIVER;
static HAL_UARTD_DRIVER;
static HAL_UARTE_DRIVER;
static HAL_UARTF_DRIVER;
static HAL_UARTG_DRIVER;
static HAL_UARTH_DRIVER;
static HAL_UARTI_DRIVER;
static HAL_UARTJ_DRIVER;
#else
static Empty::UARTDriver uartADriver;
static Empty::UARTDriver uartBDriver;
static Empty::UARTDriver uartCDriver;
static Empty::UARTDriver uartDDriver;
static Empty::UARTDriver uartEDriver;
static Empty::UARTDriver uartFDriver;
static Empty::UARTDriver uartGDriver;
static Empty::UARTDriver uartHDriver;
static Empty::UARTDriver uartIDriver;
static Empty::UARTDriver uartJDriver;
#endif

2.3 HAL_ESP32

支持3个UART,uartB用于TCP通信,uartC用于UDP通信,uartD正常硬件串口。

libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp

static Empty::UARTDriver uartADriver;
static ESP32::UARTDriver cons(0);
static ESP32::UARTDriver uartBDriver(1);
#ifdef HAL_ESP32_WIFI
#if HAL_ESP32_WIFI == 1
static ESP32::WiFiDriver uartCDriver; //tcp, client should connect to 192.168.4.1 port 5760
#elif HAL_ESP32_WIFI == 2
static ESP32::WiFiUdpDriver uartCDriver; //udp
#endif
#else
static Empty::UARTDriver uartCDriver;
#endif
static ESP32::UARTDriver uartDDriver(2);
static Empty::UARTDriver uartEDriver;
static Empty::UARTDriver uartFDriver;
static Empty::UARTDriver uartGDriver;
static Empty::UARTDriver uartHDriver;
static Empty::UARTDriver uartIDriver;
static Empty::UARTDriver uartJDriver;

2.4 HAL_Linux

支持10个UART,其中第0个uartA定义为Console。

libraries/AP_HAL_Linux/HAL_Linux_Class.cpp

static UARTDriver uartADriver(true);
static UARTDriver uartCDriver(false);
static UARTDriver uartDDriver(false);
static UARTDriver uartEDriver(false);
static UARTDriver uartFDriver(false);
static UARTDriver uartGDriver(false);
static UARTDriver uartHDriver(false);
static UARTDriver uartIDriver(false);
static UARTDriver uartJDriver(false);

2.5 HAL_SITL

支持10个UART。

https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp

static UARTDriver sitlUart0Driver(0, &sitlState);
static UARTDriver sitlUart1Driver(1, &sitlState);
static UARTDriver sitlUart2Driver(2, &sitlState);
static UARTDriver sitlUart3Driver(3, &sitlState);
static UARTDriver sitlUart4Driver(4, &sitlState);
static UARTDriver sitlUart5Driver(5, &sitlState);
static UARTDriver sitlUart6Driver(6, &sitlState);
static UARTDriver sitlUart7Driver(7, &sitlState);
static UARTDriver sitlUart8Driver(8, &sitlState);
static UARTDriver sitlUart9Driver(9, &sitlState);

SITL mapping

ParamPrefix Sim_vehicle Cmd Line Def Role Default Connection
SERIAL0_ - -uartA= or - -serial0= Console tcp:localhost:5760:wait
SERIAL1_ - -uartB= or - -serial1= MAVLink tcp:localhost:5762
SERIAL2_ - -uartC= or - -serial2= MAVLink tcp:localhost:5763
SERIAL3_ - -uartD= or - -serial3= GPS Simulated GPS
SERIAL4_ - -uartE= or - -serial4= GPS Simulated GPS
SERIAL5_ - -uartF= or - -serial5=
SERIAL6_ - -uartG= or - -serial6=
SERIAL7_ - -uartH= or - -serial7=
SERIAL8_ - -uartI= or - -serial8=
SERIAL9_ - -uartJ= or - -serial9=

参考命令

# sim_vehicle.py --console --map -A --serial5=uart:/dev/ttyS15:115200

3. 配置参数

3.1 SERIALx_BAUD

Value Meaning
1 1200
2 2400
4 4800
9 9600
19 19200
38 38400
57 57600
111 111100
115 115200
230 230400
256 256000
460 460800
500 500000
921 921600
1500 1500000
2000 2000000

3.2 SERIALx_PROTOCOL

Value Meaning
-1 None
1 MAVLink1
2 MAVLink2
3 Frsky D
4 Frsky SPort
5 GPS
7 Alexmos Gimbal Serial
8 SToRM32 Gimbal Serial
9 Rangefinder
10 FrSky SPort Passthrough (OpenTX)
11 Lidar360
13 Beacon
14 Volz servo out
15 SBus servo out
16 ESC Telemetry
17 Devo Telemetry
18 OpticalFlow
19 RobotisServo
20 NMEA Output
21 WindVane
22 SLCAN
23 RCIN
24 EFI Serial
25 LTM
26 RunCam
27 HottTelem
28 Scripting
29 Crossfire VTX
30 Generator
31 Winch
32 MSP
33 DJI FPV
34 AirSpeed
35 ADSB
36 AHRS
37 SmartAudio
38 FETtecOneWire
39 Torqeedo
40 AIS
41 CoDevESC
42 DisplayPort
43 MAVLink High Latency
44 IRC Tramp

3.3 SERIALx_OPTIONS

Value Meaning
bit0 InvertRX
bit1 InvertTX
bit2 HalfDuplex
bit3 Swap
bit4 RX_PullDown
bit5 RX_PullUp
bit6 TX_PullDown
bit7 TX_PullUp
bit8 RX_NoDMA
bit9 TX_NoDMA
bit10 Don’t forward mavlink to/from
bit11 DisableFIFO
bit12 Ignore Streamrate

3.4 SERIAL_PASSx

Value Meaning
-1 Disabled
0 Serial0
1 Serial1
2 Serial2
3 Serial3
4 Serial4
5 Serial5
6 Serial6

3.5 SERIAL_PASSTIMO

Range Units
0 to 120 seconds

4. UART常用函数

  • printf - formatted print
  • printf_P - formatted print with progmem string (saves memory on AVR boards)
  • println - print and line feed
  • write - write a bunch of bytes
  • read - read some bytes
  • available - check if any bytes are waiting
  • txspace - check how much outgoing buffer space is available
  • get_flow_control - check if the UART has flow control capabilities

5. 示例代码

libraries/AP_HAL/examples/UART_test 它向前5个UART打印一条问候信息。

可以在测试飞控板上试试,看看是否可以使用USB串行适配器显示所有输出,以及调整波特率。

/*
  simple test of UART interfaces
 */

#include 

#if HAL_OS_POSIX_IO
#include 
#endif

void setup();
void loop();

const AP_HAL::HAL& hal = AP_HAL::get_HAL();

/*
  setup one UART at 57600
 */
static void setup_uart(AP_HAL::UARTDriver *uart, const char *name)
{
    if (uart == nullptr) {
        // that UART doesn't exist on this platform
        return;
    }
    uart->begin(57600);
}


void setup(void)
{
    /*
      start all UARTs at 57600 with default buffer sizes
    */

    hal.scheduler->delay(1000); //Ensure that the uartA can be initialized

    setup_uart(hal.serial(0), "SERIAL0");  // console
    setup_uart(hal.serial(1), "SERIAL1");  // telemetry 1
    setup_uart(hal.serial(2), "SERIAL2");  // telemetry 2
    setup_uart(hal.serial(3), "SERIAL3");  // 1st GPS
    setup_uart(hal.serial(4), "SERIAL4");  // 2nd GPS
}

static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
{
    if (uart == nullptr) {
        // that UART doesn't exist on this platform
        return;
    }
    uart->printf("Hello on UART %s at %.3f seconds\n",
                 name, (double)(AP_HAL::millis() * 0.001f));
}

void loop(void)
{
    test_uart(hal.serial(0), "SERIAL0");
    test_uart(hal.serial(1), "SERIAL1");
    test_uart(hal.serial(2), "SERIAL2");
    test_uart(hal.serial(3), "SERIAL3");
    test_uart(hal.serial(4), "SERIAL4");

    // also do a raw printf() on some platforms, which prints to the
    // debug console
#if HAL_OS_POSIX_IO
    ::printf("Hello on debug console at %.3f seconds\n", (double)(AP_HAL::millis() * 0.001f));
#endif

    hal.scheduler->delay(1000);
}

AP_HAL_MAIN();

6. 参考资料

【1】ArduPilot开源飞控系统之简单介绍
【2】ArduPilot之开源代码框架
【3】ArduPilot飞控之ubuntu22.04-SITL安装
【4】ArduPilot飞控之ubuntu22.04-Gazebo模拟
【5】ArduPilot飞控之Mission Planner模拟
【6】ArduPilot飞控AOCODARC-H7DUAL固件编译
【7】ArduPilot之开源代码Library&Sketches设计
【8】ArduPilot之开源代码Sensor Drivers设计
【9】ArduPilot之开源代码基础知识&Threading概念

你可能感兴趣的:(ArduPilot,STM32,嵌入式,单片机,ArduPilot)