3、部分功能介绍(3.6 ArduPilot 解锁操作流程详解(以Copter为例))

3、部分功能介绍

  • 3.1-3.5小节内容请看其他章节。

3.6. ArduPilot 解锁操作流程详解(以Copter为例)

3.6.1. 概述

ArduPilot 中的解锁(arm)操作是一个多层次的安全检查流程,确保飞行器只有在所有安全条件都满足的情况下才能解锁。从代码可以看到,Copter 类中包含了 AP_Arming_Copter arming 成员变量,这是解锁管理的核心组件。解锁指令调用流程如下所示:

MAVLink解锁命令 → AP_Arming → AP_Arming_Copter → AP_Motors::armed()

3.6.2. 解锁系统架构

3.6.2.1. 类继承关系

1、类继承关系

AP_Arming (基类)
    ↓
AP_Arming_Copter (Copter专用解锁类)

2、单例模式绑定

// 在 Copter.h 中声明
class Copter : public AP_Vehicle {
    // Arming/Disarming management class
    AP_Arming_Copter arming;  // 实例化解锁管理器
};

// 通过单例模式全局访问
AP::arming()  // 返回当前飞行器的解锁实例

3.6.3. 解锁触发方式

解锁可以通过多种方式触发:

方式描述枚举值
方向舵解锁通过遥控器方向舵操作Method::RUDDER
MAVLink命令地面站或脚本发送Method::MAVLINK
辅助开关遥控器辅助开关Method::AUXSWITCH
电机测试电机测试模式Method::MOTORTEST
脚本触发Lua脚本控制Method::SCRIPTING
DDS接口外部DDS系统Method::DDS

3.6.4. 解锁流程核心函数

主解锁函数:arm()

bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
{
    if (armed) { //already armed
        return false;
    }

    running_arming_checks = true;  // 标记正在进行解锁检查

    if ((!do_arming_checks && mandatory_checks(true)) || 
        (pre_arm_checks(true) && arm_checks(method))) {
        
        armed = true;                           // 设置解锁状态
        last_arm_time_us = AP_HAL::micros64(); // 记录解锁时间
        _last_arm_method = method;              // 记录解锁方式
        
        Log_Write_Arm(!do_arming_checks, method); // 记录日志
        
    } else {
        armed = false;
    }

    running_arming_checks = false;
    return armed;
}

3.6.5. 三级安全检查体系

3.6.5.1. 第一级:强制检查 (Mandatory Checks)

特点:即使禁用了常规检查,这些检查也必须通过

bool AP_Arming::mandatory_checks(bool report)
{
    bool ret = true;
#if AP_OPENDRONEID_ENABLED
    ret &= opendroneid_checks(report);      // OpenDroneID 检查
#endif
    ret &= rc_in_calibration_check(report); // 遥控器校准检查
    ret &= serial_protocol_checks(report);  // 串口协议检查
    return ret;
}
3.6.5.2. 第二级:预解锁检查 (Pre-arm Checks)

特点:全面的系统组件检查,涵盖所有传感器和子系统

bool AP_Arming::pre_arm_checks(bool report)
{
    bool checks_result = 
        hardware_safety_check(report)        // 硬件安全开关
        & heater_min_temperature_checks(report)  // 加热器温度
        & barometer_checks(report)            // 气压计
        & ins_checks(report)                  // 惯性传感器 (IMU)
        & compass_checks(report)              // 指南针
        & gps_checks(report)                  // GPS
        & battery_checks(report)              // 电池
        & logging_checks(report)              // 日志系统
        & manual_transmitter_checks(report)   // 遥控器
        & mission_checks(report)              // 任务检查
        & rangefinder_checks(report)          // 测距仪
        & servo_checks(report)                // 舵机
        & board_voltage_checks(report)        // 电压检查
        & system_checks(report)               // 系统检查
        & terrain_checks(report)              // 地形检查
        & can_checks(report)                  // CAN总线
        & generator_checks(report)            // 发电机
        & proximity_checks(report)            // 接近传感器
        & camera_checks(report)               // 摄像头
        & osd_checks(report)                  // OSD显示
        & mount_checks(report)                // 云台
        & fettec_checks(report)               // FETtec电调
        & visodom_checks(report)              // 视觉里程计
        & aux_auth_checks(report)             // 辅助授权
        & disarm_switch_checks(report)        // 解除武装开关
        & fence_checks(report)                // 地理围栏
        & opendroneid_checks(report)          // OpenDroneID
        & crashdump_checks(report)            // 崩溃转储
        & serial_protocol_checks(report)      // 串口协议
        & estop_checks(report);               // 急停检查

    return checks_result;
}
3.6.5.3. 第三级:解锁时检查 (Arm Checks)

特点:在实际解锁时进行的最终检查

bool AP_Arming::arm_checks(AP_Arming::Method method)
{
    // 遥控器检查
    if (check_enabled(Check::RC)) {
        if (!rc_arm_checks(method)) {
            return false;
        }
    }

    // GPS驱动器准备
    if (check_enabled(Check::GPS_CONFIG)) {
        if (!AP::gps().prepare_for_arming()) {
            return false;
        }
    }

    // 准备日志记录
    AP_Logger *logger = AP_Logger::get_singleton();
    if (logger->logging_present()) {
        logger->PrepForArming();
        if (!logger->logging_started() && check_enabled(Check::LOGGING)) {
            check_failed(Check::LOGGING, true, "Logging not started");
            return false;
        }
    }

    return true;
}

3.6.6. 解锁成功后的操作

解锁成功后系统会执行一系列初始化操作:

if (armed && do_arming_checks && checks_to_perform == 0) {
    GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Warning: Arming Checks Disabled");
}

// FFT 子系统准备
AP_GyroFFT *fft = AP::fft();
if (fft != nullptr) {
    fft->prepare_for_arming();
}

// 地形系统设置参考位置
auto *terrain = AP::terrain();
if (terrain != nullptr) {
    terrain->set_reference_location();
}

// 自动启用地理围栏
auto *fence = AP::fence();
if (fence != nullptr) {
    fence->auto_enable_fence_on_arming();
}

// 更新 GPIO 状态
update_arm_gpio();

3.6.7. 不同飞行器的专用解锁流程

在Copter中存在一个对象,AP_Arming_Copter arming,其中的AP_Arming_CopterAP_Arming的派生类。 AP_Arming_Copter arming创建时,调用AP_Arming_Copter的构造函数,自动调用AP_Arming构造函数,实例化AP_Arming基类对象;同时,在派生类中,重新实现了arm方法。

bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_checks)
{
    // 调用基类解锁检查
    if (!AP_Arming::arm(method, do_arming_checks)) {
        return false;
    }

    // 设置电机解锁状态
    copter.motors->armed(true);
    
    // 其他 Copter 专用操作...
    
    return true;
}

3.6.8. 数据流走向:

地面站MAVLink命令
    ↓
GCS_MAVLINK::handle_command_component_arm_disarm()
    ↓
AP::arming().arm(AP_Arming::Method::MAVLINK, checks)
    ↓
AP_Arming_Copter::arm() [重写父类方法]
    ↓
AP_Arming::arm() [调用父类进行检查][检查通过]
AP_Arming::armed = true [设置解锁系统状态][返回到子类]
copter.motors->armed(true) [设置电机库状态]
    ↓
AP_Motors::_armed = true [电机库内部状态]

3.6.9. 解锁流程总结

  • 触发解锁 - 通过多种方式(遥控器、MAVLink、开关等)
  • 状态检查 - 检查当前是否已解锁
  • 强制检查 - 执行无法跳过的安全检查
  • 预解锁检查 - 全面的系统组件检查
  • 解锁时检查 - 最终的遥控器和日志检查
  • 设置解锁状态 - 更新内部状态变量
  • 记录日志 - 记录解锁事件
  • 系统初始化 - 准备各子系统进入飞行状态
  • 硬件控制 - 实际控制电机和其他执行器
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值