ArduPilot开源代码之RCInput

1. 源由

对航模的控制方法中最为直接的是通过遥控器RC进行控制。当然除此之外,也有地面站、伴机电脑等控制方式。

FPV航模领域常使用的控制方法是使用RC控制器远程控制。当下无人机的控制方法,更多是采用RC遥控+地面站软件进行控制,而地面站软件上更多是一种飞行路径规划和视频监控。

当地面站对无人机进行飞行路径规划后,采用自动导航执行路点功能实现无人自主飞行。

个人认为:从操控的角度航模FPV通过RC链路控制具有更好的飞行感受。相较于无人机来说,也更具第一人称感受,更具有身临其境的体验。

尤其当下无人机应用,环境感知传感器较少且伴机电脑功能不是很强大的情况下,当遇到异常情况时,从快速反应的角看度,FPV航模通过遥控执行飞行会更具灵活性和安全性。

为此,这里针对RC遥控控制链路进行研读,期望能够了解飞控如何与RC遥控接收机进行集成的。

2. RCInput模块入口

从飞控的角度,将RC遥控接收机作为一个RCInput(源),其类型可以分为:

enum class RCSource {
    NONE = 0,
    IOMCU = 1,
    RCPROT_PULSES = 2,
    RCPROT_BYTES = 3,
    APRADIO = 4,
} last_source;

注:通常飞控基本上用到的是IOMCU/RCPROT_PULSES/RCPROT_BYTES。

2.1 模块初始化

抽象为const AP_HAL::HAL& hal = AP_HAL::get_HAL();rcin进行初始化。

AP_Vehicle::setup
 └──> Copter::init_ardupilot
     └──> AP_BoardConfig::init
         └──> AP_BoardConfig::board_setup
             └──> hal.rcin->init

2.2 任务线程

这里开了一个后台线程,单独给RCInput模块进行使用。

main_loop
 └──> Scheduler::init
     └──> Scheduler::_rcin_thread
         └──> RCInput::_timer_tick

3. RCInput模块重要实现

3.1 常规定义

通常情况下常使用到的RC遥控接收机使用如下协议,此时需要使能AP_RCPROTOCOL_ENABLED

const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
{
    switch (protocol) {
#if AP_RCPROTOCOL_PPMSUM_ENABLED
    case PPMSUM:
        return "PPM";
#endif
#if AP_RCPROTOCOL_IBUS_ENABLED
    case IBUS:
        return "IBUS";
#endif
#if AP_RCPROTOCOL_SBUS_ENABLED
    case SBUS:
        return "SBUS";
#endif
#if AP_RCPROTOCOL_SBUS_NI_ENABLED
    case SBUS_NI:
        return "SBUS";
#endif
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
    case FASTSBUS:
        return "FastSBUS";
#endif
    case DSM:
        return "DSM";
#if AP_RCPROTOCOL_SUMD_ENABLED
    case SUMD:
        return "SUMD";
#endif
#if AP_RCPROTOCOL_SRXL_ENABLED
    case SRXL:
        return "SRXL";
#endif
#if AP_RCPROTOCOL_SRXL2_ENABLED
    case SRXL2:
        return "SRXL2";
#endif
#if AP_RCPROTOCOL_CRSF_ENABLED
    case CRSF:
        return "CRSF";
#endif
#if AP_RCPROTOCOL_ST24_ENABLED
    case ST24:
        return "ST24";
#endif
#if AP_RCPROTOCOL_FPORT_ENABLED
    case FPORT:
        return "FPORT";
#endif
#if AP_RCPROTOCOL_FPORT2_ENABLED
    case FPORT2:
        return "FPORT2";
#endif
    case NONE:
        break;
    }
    return nullptr;
}

注:PWM接收机可以选用ICU或者EICU驱动,此时需要使能HAL_USE_ICU或者HAL_USE_EICU,可参考:ChibiOS ICU Driver

3.2 H743飞控默认

H743飞控板,从配置角度主要使能了AP_RCPROTOCOL_ENABLEDHAL_USE_EICUAP_RCPROTOCOL_CRSF_ENABLED

详见:libraries/AP_RCProtocol/AP_RCProtocol_config.h

#ifndef AP_RCPROTOCOL_ENABLED
#define AP_RCPROTOCOL_ENABLED 1
#endif

详见:H743-Copter-4.3.7.zip

// RC input config
#define HAL_USE_EICU TRUE
#define STM32_EICU_USE_TIM1 TRUE
#define RCININT_EICU_TIMER EICUD1
#define RCININT_EICU_CHANNEL EICU_CHANNEL_3

详见:libraries/AP_RCProtocol/AP_RCProtocol_config.h

#ifndef AP_RCPROTOCOL_CRSF_ENABLED
#define AP_RCPROTOCOL_CRSF_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
#endif

3.3 RCInput::init

RCInput::init
 ├──> <AP_RCPROTOCOL_ENABLED> AP::RC().init()
 ├──> <HAL_USE_ICU>  //attach timer channel on which the signal will be received
 │   ├──> sig_reader.attach_capture_timer(&RCIN_ICU_TIMER, RCIN_ICU_CHANNEL, STM32_RCIN_DMA_STREAM, STM32_RCIN_DMA_CHANNEL)
 │   └──> pulse_input_enabled = true
 ├──> <HAL_USE_EICU>
 │   ├──> sig_reader.init(&RCININT_EICU_TIMER, RCININT_EICU_CHANNEL)
 │   └──> pulse_input_enabled = true
 └──> _init = true

这里AP::RC().init()对串行接收机的协议栈进行了初始化。

详见:libraries/AP_RCProtocol/AP_RCProtocol.cpp

void AP_RCProtocol::init()
{
#if AP_RCPROTOCOL_PPMSUM_ENABLED
    backend[AP_RCProtocol::PPMSUM] = new AP_RCProtocol_PPMSum(*this);
#endif
#if AP_RCPROTOCOL_IBUS_ENABLED
    backend[AP_RCProtocol::IBUS] = new AP_RCProtocol_IBUS(*this);
#endif
#if AP_RCPROTOCOL_SBUS_ENABLED
    backend[AP_RCProtocol::SBUS] = new AP_RCProtocol_SBUS(*this, true, 100000);
#endif
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
    backend[AP_RCProtocol::FASTSBUS] = new AP_RCProtocol_SBUS(*this, true, 200000);
#endif
    backend[AP_RCProtocol::DSM] = new AP_RCProtocol_DSM(*this);
#if AP_RCPROTOCOL_SUMD_ENABLED
    backend[AP_RCProtocol::SUMD] = new AP_RCProtocol_SUMD(*this);
#endif
#if AP_RCPROTOCOL_SRXL_ENABLED
    backend[AP_RCProtocol::SRXL] = new AP_RCProtocol_SRXL(*this);
#endif
#if AP_RCPROTOCOL_SBUS_NI_ENABLED
    backend[AP_RCProtocol::SBUS_NI] = new AP_RCProtocol_SBUS(*this, false, 100000);
#endif
#if AP_RCPROTOCOL_SRXL2_ENABLED
    backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this);
#endif
#if AP_RCPROTOCOL_CRSF_ENABLED
    backend[AP_RCProtocol::CRSF] = new AP_RCProtocol_CRSF(*this);
#endif
#if AP_RCPROTOCOL_FPORT2_ENABLED
    backend[AP_RCProtocol::FPORT2] = new AP_RCProtocol_FPort2(*this, true);
#endif
#if AP_RCPROTOCOL_ST24_ENABLED
    backend[AP_RCProtocol::ST24] = new AP_RCProtocol_ST24(*this);
#endif
#if AP_RCPROTOCOL_FPORT_ENABLED
    backend[AP_RCProtocol::FPORT] = new AP_RCProtocol_FPort(*this, true);
#endif
}

3.4 RCInput::_timer_tick

在定时轮训过程RCInput会负责协议侦测、握手、通信,确保RCInput内部数据最新。

RCInput::_timer_tick
 ├──> <!_init> return //未初始化
 ├──> <UARTDRIVER> //串口接收机
 │   ├──> const char *rc_protocol = nullptr
 │   └──> RCSource source = last_source
 ├──> <AP_RCPROTOCOL_ENABLED> //串口接收机协议
 │   ├──> AP_RCProtocol &rcprot = AP::RC()
 │   ├──> <HAL_USE_ICU> <pulse_input_enabled> AP_RCProtocol::process_pulse_list
 │   └──> <HAL_USE_EICU> <pulse_input_enabled> AP_RCProtocol::process_pulse
 ├──> <switch>
 │   ├──> <HAL_WITH_IO_MCU> const bool have_iocmu_rc = (_rcin_last_iomcu_ms != 0 && now - _rcin_last_iomcu_ms < 400)
 │   └──> <AP_RCPROTOCOL_ENABLED || HAL_RCINPUT_WITH_AP_RADIO> const bool have_iocmu_rc = false
 ├──> <AP_RCPROTOCOL_ENABLED> <rcprot.new_input() && !have_iocmu_rc>
 │   ├──> AP_RCProtocol::num_channels
 │   ├──> AP_RCProtocol::read
 │   ├──> AP_RCProtocol::get_RSSI
 │   ├──> AP_RCProtocol::get_rx_link_quality
 │   └──> <UARTDRIVER>
 │       ├──> AP_RCProtocol::protocol_name
 │       └──> source = rcprot.using_uart() ? RCSource::RCPROT_BYTES : RCSource::RCPROT_PULSES
 ├──> <HAL_RCINPUT_WITH_AP_RADIO> <radio && radio->last_recv_us() != last_radio_us && !have_iocmu_rc>
 │   ├──> AP_RADIO::read
 │   └──> <UARTDRIVER>
 │       └──> source = RCSource::APRADIO
 ├──> <HAL_WITH_IO_MCU> <AP_BoardConfig::io_enabled() && iomcu.check_rcinput(last_iomcu_us, _num_channels, _rc_values, RC_INPUT_MAX_CHANNELS>
 │   └──> <UARTDRIVER>
 │       ├──> rc_protocol = iomcu.get_rc_protocol()
 │       ├──> _rssi = iomcu.get_RSSI()
 │       └──> source = RCSource::IOMCU
 └──> <UARTDRIVER> <rc_protocol && (rc_protocol != last_protocol || source != last_source)>
     ├──> last_protocol = rc_protocol
     ├──> last_source = source
     └──> GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "RCInput: decoding %s(%u)", last_protocol, unsigned(source))

4. 总结

RCInput中最重要的数据:

  • _num_channels:num_channels
  • _rc_values:read
  • _rssi:get_rssi
  • _rx_link_quality:get_rx_link_quality

注:关于这些数据的应用,后面在进行详细探讨。

class ChibiOS::RCInput : public AP_HAL::RCInput {
public:
    void init() override;
    bool new_input() override;
    uint8_t num_channels() override;
    uint16_t read(uint8_t ch) override;
    uint8_t read(uint16_t* periods, uint8_t len) override;

    /* enable or disable pulse input for RC input. This is used to
       reduce load when we are decoding R/C via a UART */
    void pulse_input_enable(bool enable) override;

    int16_t get_rssi(void) override {
        return _rssi;
    }
    int16_t get_rx_link_quality(void) override {
        return _rx_link_quality;
    }
    const char *protocol() const override { return last_protocol; }

    void _timer_tick(void);
    bool rc_bind(int dsmMode) override;

private:
    uint16_t _rc_values[RC_INPUT_MAX_CHANNELS] = {0};

    uint64_t _last_read;
    uint8_t _num_channels;
    Semaphore rcin_mutex;
    int16_t _rssi = -1;
    int16_t _rx_link_quality = -1;
    uint32_t _rcin_timestamp_last_signal;
#if HAL_WITH_IO_MCU
    uint32_t _rcin_last_iomcu_ms;
#endif
    bool _init;
    const char *last_protocol;

    enum class RCSource {
        NONE = 0,
        IOMCU = 1,
        RCPROT_PULSES = 2,
        RCPROT_BYTES = 3,
        APRADIO = 4,
    } last_source;

    bool pulse_input_enabled;

#if HAL_RCINPUT_WITH_AP_RADIO
    bool _radio_init;
    AP_Radio *radio;
    uint32_t last_radio_us;
#endif

#if HAL_USE_ICU == TRUE
    ChibiOS::SoftSigReader sig_reader;
#endif

#if HAL_USE_EICU == TRUE
    ChibiOS::SoftSigReaderInt sig_reader;
#endif

#if HAL_WITH_IO_MCU
    uint32_t last_iomcu_us;
#endif
};

5. 参考资料

【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概念
【10】ArduPilot之开源代码UARTs and the Console使用
【11】ArduPilot飞控启动&运行过程简介
【11】ArduPilot之开源代码Task介绍
【12】ArduPilot开源代码之AP_Param
【13】ArduPilot开源代码之AP_Scheduler
【14】ArduPilot开源代码之AP_VideoTX
【15】ArduPilot开源代码之AP_InertialSensor_Backend
【16】ArduPilot开源代码之AP_InertialSensor
【17】ArduPilot开源代码之AP_Logger
【18】ArduPilot开源代码之AP_GPS

猜你喜欢

转载自blog.csdn.net/lida2003/article/details/131503263
今日推荐