Ardupilot通过mavlink + 4way_protocol对BLHeli_s电调的读写

2023-05-16

Ardupilot通过mavlink + 4way_protocol对BLHeli_s电调的读写

  • 前言
  • 上位机
    • 1、Mission Planner
    • 2、BLHeliSuite
    • 3、BLHeliSuite32
  • Ardupilot 源码编译
    • 1、启动BLHeli_s支持
    • 2、修改打印连接信息方式
    • 3、编译源码
      • 1、板子配置及编译
      • 2、固件烧录
  • 参数配置
  • BL地面站连接
    • 1、连接地面站
    • 2、读取电调
  • Ardupilot 对BLHeli_s 8位的操作不成功疑惑
    • 1、8位地面站连接
    • 2、尝试读取电调配置
    • 3、查看Ardupilot 是否有对8位的读写接口

前言

当装机完成之后,发现电调与电机匹配不太好,或者转向相反,各种拆线很难受。BetaFlight飞控可支持通过信号线对BL电调进行读写,那么Ardupilot、PX4这两来源飞控系统呢? 答案是支持的,本文以Ardupilot为例记录我踩的坑以及对其不能连接8位BL电调的疑惑。

上位机

1、Mission Planner

Ardupilot地面站软件,本文使用它来对参数进行修改配置

2、BLHeliSuite

BLHeli_s 8位电调地面站,可以对8位电调进行读写

3、BLHeliSuite32

BLHeli_s 32位电调地面站,可以对32位电调进行读写

Ardupilot 源码编译

建议大家在最新的4.0版本上编译,我先是在4.0验证之后 转到3.6版本上使用的。
本文只从4.0版本进行说明。

1、启动BLHeli_s支持

在目录ardupilot/libraries/AP_HAL下的AP_HAL_Board.h文件中修改HAL_SUPPORT_RCOUT_SERIAL为1

#ifndef HAL_SUPPORT_RCOUT_SERIAL
#define HAL_SUPPORT_RCOUT_SERIAL 1
#endif

2、修改打印连接信息方式

默认会通过mavink发送连接信息到地面站,如果没有连接数传的时候,USB接口被BL地面站占用了,就无法在飞控地面站MP 查看连接信息,所以修改到debug接口打印出来,不过这就需要外接一个USB转TTL模块。
在AP_BLHeli.c文件中修改宏定义,然后在下面的debug 后面添加 \n 让其换行

// #define debug(fmt, args ...) do { if (debug_level) { gcs().send_text(MAV_SEVERITY_INFO, "ESC: " fmt, ## args); } } while (0)
#define debug(fmt, args ...)  printf("ESC:" fmt, ## args)

例如

//debug("MSP_API_VERSION");
debug("MSP_API_VERSION\n");

3、编译源码

1、板子配置及编译

我使用的是Pixracer,可根据自己手上的飞控板进行对应的指令修改

./waf configure --board Pixracer 		//Pixracer就是飞控板的名称
./waf copter	//多旋翼固件编译

2、固件烧录

./waf --targets bin/arducopter --upload

参数配置

SERVO_BLH_DEBUG 1 //需要修改 SERVO_BLH_DEBUG 使能对BL电调的连接
具体参数看图
在这里插入图片描述
在这里插入图片描述

BL地面站连接

1、连接地面站

直接通过USB连接飞控,打开BL地面站,选择连接方式为Betaflight/Cleanfight
在这里插入图片描述
找到对应的接口然后点击Connect 连接
在这里插入图片描述
连接时 debug接口打印的信息如下:
在这里插入图片描述

2、读取电调

给电调上电,然后点击Read Setup
在这里插入图片描述
在这里插入图片描述
试着改个电机旋转方向写入测试:
在这里插入图片描述
到这里,Ardupilot 对BLHeli_s 32位电调的直接读写宣布完成

Ardupilot 对BLHeli_s 8位的操作不成功疑惑

1、8位地面站连接

在这里插入图片描述
串口输出信息:
在这里插入图片描述

2、尝试读取电调配置

可读取到32位电调的信息:
在这里插入图片描述
在这里插入图片描述
但是BL地面站 只能对应的使用,8位的不能看32位的,所以使用8位电调再测试看看

正常连接至地面站
在这里插入图片描述
在这里插入图片描述

读取电调:发现了 多旋翼电调配置, 并且是SiLabs 主控的,但是 没能连接上
在这里插入图片描述
在这里插入图片描述
在这里插入图片描述

提示说需要给电调上电,问题是电源一直给的。
说明:地面站,8位32位 电调都经过Beatflight 飞控直连测试通过,肯定了电调没有问题

3、查看Ardupilot 是否有对8位的读写接口

在BL_ConnectEx(void)函数中,发现已存在对8位的支持,0xE8B1 0xE8B2就是对应的主控为EFM8BB10、EFM8BB21
在这里插入图片描述

/*
  connect to a blheli ESC
 */
bool AP_BLHeli::BL_ConnectEx(void)
{
    if (blheli.connected[blheli.chan] != 0) {
        debug("Using cached interface 0x%x for %u\n", blheli.interface_mode[blheli.chan], blheli.chan);
        return true;
    }
    debug("BL_ConnectEx %u/%u at %u\n", blheli.chan, num_motors, motor_map[blheli.chan]);
    setDisconnected();
    const uint8_t BootInit[] = {0,0,0,0,0,0,0,0,0,0,0,0,0x0D,'B','L','H','e','l','i',0xF4,0x7D};
    if (!BL_SendBuf(BootInit, 21)) {
        return false;
    }

    uint8_t BootInfo[8];
    if (!BL_ReadBuf(BootInfo, 8)) {
        return false;
    }

    // reply must start with 471
    if (strncmp((const char *)BootInfo, "471", 3) != 0) {
        blheli.ack = ACK_D_GENERAL_ERROR;        
        return false;
    }

    // extract device information
    blheli.deviceInfo[blheli.chan][2] = BootInfo[3];
    blheli.deviceInfo[blheli.chan][1] = BootInfo[4];
    blheli.deviceInfo[blheli.chan][0] = BootInfo[5];

    blheli.interface_mode[blheli.chan] = 0;
    
    uint16_t *devword = (uint16_t *)blheli.deviceInfo[blheli.chan];
    switch (*devword) {
    case 0x9307:
    case 0x930A:
    case 0x930F:
    case 0x940B:
        blheli.interface_mode[blheli.chan] = imATM_BLB;
        debug("Interface type imATM_BLB\n");
        break;
    case 0xF310:
    case 0xF330:
    case 0xF410:
    case 0xF390:
    case 0xF850:
    case 0xE8B1:
    case 0xE8B2:
        blheli.interface_mode[blheli.chan] = imSIL_BLB;
        debug("Interface type imSIL_BLB\n");
        break;
    case 0x1F06:
    case 0x3306:
    case 0x3406:
    case 0x3506:
    case 0x2B06:
    case 0x4706:
        blheli.interface_mode[blheli.chan] = imARM_BLB;
        debug("Interface type imARM_BLB\n");
        break;
    default:
        blheli.ack = ACK_D_GENERAL_ERROR;        
        debug("Unknown interface type 0x%04x", *devword);
        break;
    }
    blheli.deviceInfo[blheli.chan][3] = blheli.interface_mode[blheli.chan];
    if (blheli.interface_mode[blheli.chan] != 0) {
        blheli.connected[blheli.chan] = true;
    }
    return true;
}

查看消息记录可以看到:查到的电机数为0
在这里插入图片描述
在这里插入图片描述
具体是将函数是void AP_BLHeli::blheli_process_command(void)

/*
  process a blheli 4way command from GCS
 */
void AP_BLHeli::blheli_process_command(void)
{
    debug("BLHeli cmd 0x%02x len=%u\n", blheli.command, blheli.param_len);
    blheli.ack = ACK_OK;
    switch (blheli.command) {
    case cmd_InterfaceTestAlive: {
        debug("cmd_InterfaceTestAlive\n");
        BL_SendCMDKeepAlive();
        if (blheli.ack != ACK_OK) {
            setDisconnected();
        }
        uint8_t b = 0;
        blheli_send_reply(&b, 1);
        break;
    }
    case cmd_ProtocolGetVersion: {
        debug("cmd_ProtocolGetVersion\n");
        uint8_t buf[1];
        buf[0] = SERIAL_4WAY_PROTOCOL_VER;
        blheli_send_reply(buf, sizeof(buf));
        break;
    }
    case cmd_InterfaceGetName: {
        debug("cmd_InterfaceGetName\n");
        uint8_t buf[5] = { 4, 'A', 'R', 'D', 'U' };
        blheli_send_reply(buf, sizeof(buf));
        break;
    }
    case cmd_InterfaceGetVersion: {
        debug("cmd_InterfaceGetVersion\n");
        uint8_t buf[2] = { SERIAL_4WAY_VERSION_HI, SERIAL_4WAY_VERSION_LO };
        blheli_send_reply(buf, sizeof(buf));
        break;
    }
    case cmd_InterfaceExit: {
        debug("cmd_InterfaceExit\n");
        msp.escMode = PROTOCOL_NONE;
        uint8_t b = 0;
        blheli_send_reply(&b, 1);
        hal.rcout->serial_end();
        serial_start_ms = 0;
        if (motors_disabled) {
            motors_disabled = false;
            SRV_Channels::set_disabled_channel_mask(0);            
        }
        if (uart_locked) {
            debug("Unlocked UART\n");
            uart->lock_port(0);
            uart_locked = false;
        }
        memset(blheli.connected, 0, sizeof(blheli.connected));
        break;
    }
    case cmd_DeviceReset: {
        debug("cmd_DeviceReset(%u)\n", unsigned(blheli.buf[0]));
        if (blheli.buf[0] >= num_motors) {
            debug("bad reset channel %u\n", blheli.buf[0]);
            blheli.ack = ACK_D_GENERAL_ERROR;
            blheli_send_reply(&blheli.buf[0], 1);            
            break;
        }
        blheli.chan = blheli.buf[0];
        switch (blheli.interface_mode[blheli.chan]) {
        case imSIL_BLB:
        case imATM_BLB:
        case imARM_BLB:
            debug("imSIL_BLB ATM  ARM bootloader\n");
            BL_SendCMDRunRestartBootloader();
            break;
        case imSK:
            break;
        }
        blheli_send_reply(&blheli.chan, 1);
        setDisconnected();
        break;
    }

    case cmd_DeviceInitFlash: {
        debug("cmd_DeviceInitFlash(%u)\n", unsigned(blheli.buf[0]));
        if (blheli.buf[0] >= num_motors) {
            debug("bad channel %u\n", blheli.buf[0]);
            break;
        }
        blheli.chan = blheli.buf[0];
        blheli.ack = ACK_OK;
        BL_ConnectEx();
        uint8_t buf[4] = {blheli.deviceInfo[blheli.chan][0],
                          blheli.deviceInfo[blheli.chan][1],
                          blheli.deviceInfo[blheli.chan][2],
                          blheli.deviceInfo[blheli.chan][3]};  // device ID
        blheli_send_reply(buf, sizeof(buf));
        break;
    }

    case cmd_InterfaceSetMode: {
        debug("cmd_InterfaceSetMode(%u)\n", unsigned(blheli.buf[0]));
        blheli.interface_mode[blheli.chan] = blheli.buf[0];
        blheli_send_reply(&blheli.interface_mode[blheli.chan], 1);
        break;
    }

    case cmd_DeviceRead: {
        uint16_t nbytes = blheli.buf[0]?blheli.buf[0]:256;
        debug("cmd_DeviceRead(%u) n=%u\n", blheli.chan, nbytes);
        uint8_t buf[nbytes];
        uint8_t cmd = blheli.interface_mode[blheli.chan]==imATM_BLB?CMD_READ_FLASH_ATM:CMD_READ_FLASH_SIL;
        if (!BL_ReadA(cmd, buf, nbytes)) {
            nbytes = 1;
        }
        blheli_send_reply(buf, nbytes);
        break;
    }

    case cmd_DevicePageErase: {
        uint8_t page = blheli.buf[0];
        debug("cmd_DevicePageErase(%u) im=%u\n", page, blheli.interface_mode[blheli.chan]);
        switch (blheli.interface_mode[blheli.chan]) {
        case imSIL_BLB:
        case imARM_BLB: {
            if  (blheli.interface_mode[blheli.chan] == imARM_BLB) {
                // Address =Page * 1024
                blheli.address = page << 10;
            } else {
                // Address =Page * 512
                blheli.address = page << 9;
            }
            debug("ARM PageErase 0x%04x\n", blheli.address);
            BL_PageErase();
            blheli.address = 0;
            blheli_send_reply(&page, 1);
            break;
        }
        default:
            blheli.ack = ACK_I_INVALID_CMD;
            blheli_send_reply(&page, 1);
            break;
        }
        break;
    }

    case cmd_DeviceWrite: {
        uint16_t nbytes = blheli.param_len;
        debug("cmd_DeviceWrite n=%u im=%u\n", nbytes, blheli.interface_mode[blheli.chan]);
        uint8_t buf[nbytes];
        memcpy(buf, blheli.buf, nbytes);
        switch (blheli.interface_mode[blheli.chan]) {
        case imSIL_BLB:
        case imATM_BLB:
        case imARM_BLB: {
            BL_WriteFlash(buf, nbytes);
            break;
        }
        case imSK: {
            debug("Unsupported flash mode imSK\n");
            break;
        }
        }
        uint8_t b=0;
        blheli_send_reply(&b, 1);        
        break;
    }

    case cmd_DeviceVerify: {
        uint16_t nbytes = blheli.param_len;
        debug("cmd_DeviceWrite n=%u im=%u\n", nbytes, blheli.interface_mode[blheli.chan]);
        switch (blheli.interface_mode[blheli.chan]) {
        case imARM_BLB: {
            uint8_t buf[nbytes];
            memcpy(buf, blheli.buf, nbytes);            
            BL_VerifyFlash(buf, nbytes);
            break;
        }
        default:
            blheli.ack = ACK_I_INVALID_CMD;
            break;
        }
        uint8_t b=0;
        blheli_send_reply(&b, 1);        
        break;
    }

    case cmd_DeviceReadEEprom: {
        uint16_t nbytes = blheli.buf[0]?blheli.buf[0]:256;
        uint8_t buf[nbytes];
        debug("cmd_DeviceReadEEprom n=%u im=%u\n", nbytes, blheli.interface_mode[blheli.chan]);
        switch (blheli.interface_mode[blheli.chan]) {
        case imATM_BLB: {
            if (!BL_ReadA(CMD_READ_EEPROM, buf, nbytes)) {
                blheli.ack = ACK_D_GENERAL_ERROR;
            }
            break;
        }
        default:
            blheli.ack = ACK_I_INVALID_CMD;
            break;
        }
        if (blheli.ack != ACK_OK) {
            nbytes = 1;
            buf[0] = 0;
        }
        blheli_send_reply(buf, nbytes);
        break;
    }

    case cmd_DeviceWriteEEprom: {
        uint16_t nbytes = blheli.param_len;
        uint8_t buf[nbytes];
        memcpy(buf, blheli.buf, nbytes);
        debug("cmd_DeviceWriteEEprom n=%u im=%u\n", nbytes, blheli.interface_mode[blheli.chan]);
        switch (blheli.interface_mode[blheli.chan]) {
        case imATM_BLB:
            BL_WriteA(CMD_PROG_EEPROM, buf, nbytes, 1000);
            break;
        default:
            blheli.ack = ACK_D_GENERAL_ERROR;
            break;
        }
        uint8_t b = 0;
        blheli_send_reply(&b, 1);
        break;
    }
        
    case cmd_DeviceEraseAll:
    case cmd_DeviceC2CK_LOW:
    default:
        // ack=unknown command
        blheli.ack = ACK_I_INVALID_CMD;
        debug("Unknown BLHeli protocol 0x%02x\n", blheli.command);
        uint8_t b = 0;
        blheli_send_reply(&b, 1);
        break;
    }
}

/*
  process an input byte, return true if we have received a whole
  packet with correct CRC
 */
bool AP_BLHeli::process_input(uint8_t b)
{
    bool valid_packet = false;
    
    if (msp.escMode == PROTOCOL_4WAY && blheli.state == BLHELI_IDLE && b == '$') {
        debug("Change to MSP mode\n");
        msp.escMode = PROTOCOL_NONE;
        hal.rcout->serial_end();
        serial_start_ms = 0;
    }
    if (msp.escMode != PROTOCOL_4WAY && msp.state == MSP_IDLE && b == '/') {
        debug("Change to BLHeli mode\n");
        memset(blheli.connected, 0, sizeof(blheli.connected));
        msp.escMode = PROTOCOL_4WAY;
    }
    if (msp.escMode == PROTOCOL_4WAY) {
        blheli_4way_process_byte(b);
    } else {
        msp_process_byte(b);
    }
    if (msp.escMode == PROTOCOL_4WAY) {
        if (blheli.state == BLHELI_COMMAND_RECEIVED) {
            valid_packet = true;
            last_valid_ms = AP_HAL::millis();
            if (uart->lock_port(BLHELI_UART_LOCK_KEY)) {
                uart_locked = true;
            }
            blheli_process_command();
            blheli.state = BLHELI_IDLE;
            msp.state = MSP_IDLE;
        }
    } else if (msp.state == MSP_COMMAND_RECEIVED) {
        if (msp.packetType == MSP_PACKET_COMMAND) {
            valid_packet = true;
            if (uart->lock_port(BLHELI_UART_LOCK_KEY)) {
                uart_locked = true;
            }
            last_valid_ms = AP_HAL::millis();
            msp_process_command();
        }
        msp.state = MSP_IDLE;
        blheli.state = BLHELI_IDLE;
    }

    return valid_packet;
}

结合源码及debug消息初步分析是地面站点击读取的时候发的0x31后直接到0x37,导致前面的配置信息都没有获取到,所以就连接不上。但还存在疑惑的是 为什么32位电调可以顺利连接,8位电调的固件版本我从16.7慢慢降低到15版本也不行。

希望能在评论区得到大佬的解答,感激不尽!!!

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

Ardupilot通过mavlink + 4way_protocol对BLHeli_s电调的读写 的相关文章

  • golang windows弹窗功能实现

    代码示例 span class token keyword package span main span class token keyword import span span class token punctuation span s
  • golang获取windows系统有线活跃网卡及IP配置

    代码 span class token keyword package span network span class token keyword import span span class token punctuation span
  • !!!Chapter 2 The Physical Layer

    2 1 The Theoretical Basis for Data Communication Fourier Analysis Any reasonably behaved periodic function g t with peri
  • 启动golang项目编译的exe可执行文件获取windows管理员权限(UAC)

    背景 xff1a go代码启动以后里面涉及到修改ip地址等操作 xff0c 需要管理员权限 打包好的exe文件双击执行默认是没有管理员权限的 xff0c 那么修改ip就会提示需要管理员权限 解决方法1 xff1a 右键以管理员权限运行exe
  • k8s外部访问pod内部容器的端口-NodePort

    一 如何从外部网络访问 Kubernetes的Pod IP和Cluster IP都只能在集群内部访问 xff0c 而我们通常需要从外部网络上访问集群中的某些服务 xff0c Kubernetes提供了下述几种方式来为集群提供外部流量入口 二
  • python断点下载文件

    使用pytohn编码实现文件的断点下载 span class token keyword import span os span class token keyword import span json span class token k
  • 异常检测(1)—初识异常检测

    1 概念 异常一般是指与标准值 xff08 预期值 xff09 有偏离的样本点 xff0c 也就是跟绝大部分数据 长的不一样 异常往往是 有价值 的事情 xff0c 我们对异常的成因感兴趣 2 类别 有监督 xff1a 数据集有标签无监督
  • 【git】在GitHub上下载历史版本

    GitHub上的项目很多都是从简单到复杂 xff0c 一点点迭代的 当我们需要看懂别人的代码时 xff0c 按照别人commit的历史版本一步一步跟踪 xff0c 或许是个好办法 这时候我们就要用到下载历史版本功能了 1 git clone
  • 实时操作系统UCOS学习笔记1----UCOSII简介

    前面我们所有的实验都是跑的裸机程序 xff08 裸奔 xff09 xff0c 从本章开始 xff0c 我们开始介绍UCOSII xff08 实时多任务操作系统内核 xff09 UCOSII简介 UCOSII的前身是UCOS xff0c 最早
  • 欢聚时代YY/测试实习面试

    去到YY大楼 xff0c 虽然在番禺但是附近很多楼在施工中了 大楼就在万达后面 前台登记 xff0c 小姐姐会让你出示邀请邮件 xff0c 然后直接上去就行了 达到楼层 xff0c 二维码签到 然后找地方坐一下等待面试 一轮是技术面 xff
  • 基于卡尔曼滤波的气压计高度解算

    ax ay az为归一化的加速度数据 1代表重力加速度 gx gy gz 为加速度数据 单位rad s altitude为气压计测量得到的海拔数据 欧拉角 float pitch roll yaw 世界坐标系下机体加速度 float ax
  • Kali安装Xfce4

    Kali安装Xface4 一 配置kali源并更新二 解决报错1 签名无效2 依赖报错 三 安装xfce4 一 配置kali源并更新 此处使用的是gedit编辑器 xff0c gedit etc apt sources list xff0c
  • 串口转WIFI的工作方式理解

    串口无线 AP xff08 COM AP xff09 串口无线 STA xff08 COM STA xff09 和 串口无线 AP 43 STA xff08 COM AP 43 STA xff09 3 个模式 串口WIFI模块是基于Uart
  • 典型环节的频率特性(建议收藏)

    自控笔记 5 3典型环节频率特性 控制系统种类繁多 xff0c 传递函数复杂 xff0c 但任何形式的传递函数都是由有限的典型环节组成 因此 xff0c 掌握典型环节的频率特性是使用频域法分析系统的基础 如下表所示 xff0c 构成系统的最
  • 【WINAPI】CreateSemaphore_信号量

    WINAPI CreateSemaphore 信号量 1 注册信号量函数1 1 参数1 2 返回值 2 释放信号量函数2 1 参数2 2 返回值 3 WaitForSingleObject3 2 参数3 3 返回值 4 例子4 1 运行结果
  • MAVROS二次开发(一)MAVROS的安装

    MAVROS二次开发 一 MAVROS的安装 1 参考网址 https dev px4 io v1 10 en ros mavros installation html https github com mavlink mavros tre
  • MAVROS二次开发(二)(三)添加自定义消息

    MAVROS二次开发 二 MAVROS消息添加 1 自定义rostopic消息 路径 xff1a catkin ws src mavros mavros msgs msg 自定义消息文件名称 xff1a CrawlControlStatus
  • MAVROS二次开发(四)添加消息处理插件

    MAVROS二次开发 四 添加消息处理插件 mavros插件所在路径 xff1a catkin ws src mavros mavros src plugins 1 自定义消息处理插件的编写 参考代码 xff1a catkin ws src
  • MAVROS二次开发(五)进行测试

    MAVROS二次开发 五 进行测试 1 测试环境 PX4 xff1a v1 10 1 xff08 含自定义mavlink消息收发 xff09 ROS xff1a KineticUbuntu xff1a 16 04LTSQGC xff1a S
  • ROS2+PX4开发环境配置

    一 ROS2安装 Ubuntu18 04的ros2版本 xff1a Eloquent 参考网址 xff1a https docs ros org en eloquent Installation Linux Install Debians

随机推荐

  • Windows10下Airsim+PX4(WSL2)+MAVROS仿真环境搭建

    一 Windows10下WSL2安装 1 1 WSL2的安装与配置 首先在Windows10下启用WSL xff0c 以管理员身份打开 PowerShell 工具并运行以下命令 dism span class token punctuati
  • Windows10通过vcpkg快速配置PCL库

    1 安装C 43 43 包管理工具vcpkg https github com microsoft vcpkg span class token function git span clone https github com micros
  • 微软Chromium版Edge浏览器正式稳定版

    微软Chromium版Edge浏览器正式稳定版 近期微软Chromium版Edge浏览器正式稳定版下载已经泄露 xff0c 版本77 0 235 9 此版本没有div什么的那些 xff0c 和之前的图标一样 当安装新Edge稳定版之后 xf
  • C++疑难问题

    acwing中的算法疑惑 1 为什么确定范围 要 43 10 在使用归并排序和快速排序等方法时有效率问题 xff0c 确定范围在1e6 但是选择的是1e 43 10 2 C 43 43 除二乘2简单方法以及算法效率问题 算法效率速度排行 x
  • 用python的scipy中的odeint来解常微分方程中的一些细节问题(适用于小白)

    用python的scipy中的odeint来解常微分方程中的一些细节问题 xff08 适用于小白 xff09 写在前面 最近有些需要解决常微分方程的问题 xff0c 网上查了很多教程都不是很明晰 xff0c 便自己研究了一段时间 xff0c
  • VsCode使用Git连接Gitee和GitHub

    VsCode连接GitHub和Gitee VsCode连接GitHub和Gitee一 软件安装1 安装git2 vscode 二 在Github或者Gitee上创建空的仓库 项目1 在Github创建空的仓库 项目2 在Gitee创建新项目
  • Julia配置【使用VScode中的Jupyter编写Julia的方法】

    简略目录 安装Julia切换国内源安装Ijulia插件VSCode配置 首次编写日期 xff1a 2021 07 10 安装Julia 官网 xff0c 一路默认即可 xff0c 记得添加PATH xff0c 安装位置可以自定义 切换国内源
  • VSCode配置C++环境(MSVC)

    VSCode配置C 43 43 环境 xff08 MSVC xff09 最近心血来潮 xff0c 想用一下微软的VSCode写一下C 43 43 xff0c 然而第一步就卡住了 xff0c 竟然不会配置C 43 43 环境 xff0c 陆陆
  • GTSAM理解

    1 xff1a GTSAM是什么 参考博文 xff1a gtsam xff1a 从入门到使用 1 xff1a 是什么 xff1a GTSAM是用于计算机视觉和多传感器融合方面用于平滑和建图的C 43 43 库 xff0c GTSAM采用因子
  • tag与branch的区别

    1 什么是tag 什么时候应该创建一个tag 项目的版本管理中 每当一个release版本发布时 需要做一个记录 以便以后需要的时候能查找特定的版本 这时候就用到tag这个功能 Git中的tag指向一次commit的id xff0c 通常用
  • 简历中“项目经历“该如何写?

    前言 找工作 xff0c 简历是最关键的一步 xff0c 只有通过了简历筛查才能往下继续进行 很多人写简历 xff0c 都是在记录流水账 xff0c 看来没有任何平淡寡味 其实简历的核心价值就在于游说 hr 和面试官 xff1a 看我 xf
  • 深度学习解释:Precision、Recall、IoU、Ap/mAp

    深度学习的指标都是 xff08 APAverage Precision xff09 二分类情况下的Precision xff08 查重率 xff09 和Recall xff08 查全率 xff09 对于二分类问题 xff0c 可将样例根据其
  • input上传文件图片本地预览

    lt form gt lt input type 61 34 file 34 id 61 34 avatar 34 name 61 34 avatar 34 gt lt button gt 点击上传 lt button gt lt form
  • colmap pthread 错误

    Looking for include file pthread h Looking for include file pthread h found Looking for pthread create Looking for pthre
  • 全球系留无人机系统行业调研及趋势分析报告

    本文调研和分析全球系留无人机系统发展现状及未来趋势 xff0c 核心内容如下 xff1a xff08 1 xff09 全球市场总体规模 xff0c 分别按销量和按收入进行了统计分析 xff0c 历史数据2017 2021年 xff0c 预测
  • 安装arm-none-eabi版本添加环境变了还是出错问题解决

    安装arm none eabi版本添加环境变了还是出错问题解决 问题解决 问题 已经在 profile文件里面添加了如下命令 span class token keyword export span span class token con
  • 基于ubuntu16.04 塔建PX4编译环境

    基于ubuntu16 04 塔建PX4编译环境 基于ubuntu16 04 塔建PX4编译环境环境塔建官网网址 xff1a 权限设定删除modemmanager更新软件包列表 xff0c 并为所有PX4构建目标安装以下依赖项 安装pyulo
  • APM编译记录-基于OMNIBUSF4-V3飞控板

    APM编译记录 基于OMNIBUSF4 V3飞控板 APM编译记录Bootloader问题固件编译 APM编译记录 初次使用APM xff0c 根据博客文章以及结合官方教程摸索 xff0c 发现和PX4还是有挺大差别的 xff0c 目前系统
  • ubuntu16.04基于eclipse搭建px4编译环境+Jlink调式

    ubuntu16 04基于eclipse搭建px4编译环境 43 Jlink调式 xff09 ubuntu16 04基于eclipse搭建px4编译环境 43 Jlink调式一 工具获取1 eclipse2 jlink3 jdk4 arm
  • Ardupilot通过mavlink + 4way_protocol对BLHeli_s电调的读写

    Ardupilot通过mavlink 43 4way protocol对BLHeli s电调的读写 前言上位机1 Mission Planner2 BLHeliSuite3 BLHeliSuite32 Ardupilot 源码编译1 启动B