ZED 2i 双目-IMU标定

2023-05-16

目录:

  • 前言
  • IMU标定
    • 1、编译标定工具
    • 2、准备数据集
    • 3、标定
  • Camera-IMU标定
    • 1、安装依赖
    • 2、编译Kaibr
    • 3、制作标定板
      • 下载标定板
      • 生成标定板
      • target.yaml文件
    • 4、数据采集
    • 5、相机标定
      • 标定中遇到的问题
        • 问题1:
        • 问题2
      • 标定结果查看
    • 6、相机-IMU外参标定
      • 收集数据
      • 标定
      • 标定结果

前言

最近团队买了一个ZED 2i双目相机,之前也做过一些其他一些相机的标定比如 realsence d435i,但之前都没有对标定整个流程整理过,现在刚好趁标定这个新相机对标定的一些流程做一次整理,方便以后查看

image-20220915205950814

IMU标定

标定IMU的白噪声和bias游走时,有两个常用的开源工具,一个是imu_utils,一个是kalibr_allan,都是计算IMU随机误差的Allan方差的。本文主要使用的是imu_utils进行IMU的标定。

Allan方差是将误差序列在某个指定的时间尺度上的波动情况进行了精确提取,其具体计算步骤如下:

  1. 将整段误差序列按设定的时间尺度的长度(例如1分钟)进行分块;

通过分块确定所要考察的时间块长度;

  1. 每块求平均值;

利用块内求平均的办法把短于块长度的那些快速变化成份(细节)都抹掉;

  1. 相邻块的平均值求差;

利用相邻块求差的办法把长于两块长度的那些缓慢变化成份(宏观)都抹掉

  1. 将所有差值进行统计,得到其均方值,并乘以1/2。

最后对差值序列统计其均方值(这是处理任何随机样本的标准操作),这样统计出来的就是介于1倍块长度和2倍块长度这样一个很窄的时间尺度范围内的误差波动情况。

参考:Allan方差分析方法的直观理解

1、编译标定工具

使用 imu_utils 进行标定,它依赖ceres-solver优化库,要先安装ceres库

另外,imu_utils是依赖于code_utils的,所以先编译code_utils后再下载编译imu_utils

cd  ~/calibration_ws/src
git clone https://github.com/gaowenliang/code_utils
cd ..
catkin_make

编译报错一:

fatal error: backward.hpp:No such file or directory
  • 解决方法:打开工程将sumpixel_test.cpp中的#include “backward.hpp"修改为#include “code_utils/backward.hpp”

编译报错二:

code_utils/backward.hpp:216:30: fatal error: elfutils/libdw.h: No such file or directory
  • 解决办法:安装libdw-dev库,sudo apt install libdw-dev

编译成功code_utils之后,下载编译imu_utils

cd  ~/calibration_ws/src
git clone https://github.com/gaowenliang/imu_utils
cd ..
catkin_make

2、准备数据集

静止IMU,录制一段两个小时左右的 /imu_topic 的数据,用于之后回放标定

rosbag record -O zed-imu-calibrate.bag /zed2i/zed_node/imu/data_raw

image-20220916164056962

3、标定

编写一个launch文件,启动标定工具。这里以我标定ZED 2i内部的IMU为例,如下:

<launch>
    <node pkg="imu_utils" type="imu_an" name="imu_an" output="screen">
        <!-- 数据集的话题 -->
        <param name="imu_topic" type="string" value= "/zed2i/zed_node/imu/data_raw"/>
        <!-- IMU的名字,后面生成的标定文件会附带这个名字作为标记 -->
        <param name="imu_name" type="string" value= "zed_imu"/>
        <!-- 标定结果输出路径 -->
        <param name="data_save_path" type="string" value= "/home/linzs/ZED_calib/imu_calib"/>
        <!-- 数据集的长度,单位:分钟 -->
        <param name="max_time_min" type="int" value= "170"/>
        <!-- Allan方差的cluster,一般设置100即可 -->
        <param name="max_cluster" type="int" value= "100"/>
    </node>
</launch>

之后就是播放录制的数据集,以及运行上面的launch文件,

image-20220916185940458

播放数据集的时候可以加速播放,我这里是加速了200倍

image-20220916190014645

最后会生成标定文件如下:

image-20220916193507150

Camera-IMU标定

相机的内参可以通过读取/camera/color/camera_info话题获得,如果没有这个话题也可以通过Kaibr标定出来

image-20220915210657800

其实,这个ZED 2i相机的话题特别多,里面就包含了相机内参和外参信息发布的话题,但是为了记录标定流程这里还是按标定流程来进行记录

使用 Kalibr 标定双目相机内外参数以及和IMU之间外参数。Kaibr在SLAM领域比较出名,它提供多相机系统、相机-IMU系统互标定的功能

Kailbr 使用手册 https://slightech.github.io/MYNT-EYE-S-SDK-Guide/src/slam/how_to_use_kalibr.html

1、安装依赖

$ sudo apt install python-setuptools python-rosinstall ipython libeigen3-dev libboost-all-dev doxygen libopencv-dev
$ sudo apt install ros-noetic-vision-opencv ros-noetic-image-transport-plugins ros-noetic-cmake-modules
$ sudo apt install python-software-properties software-properties-common libpoco-dev python-matplotlib python-scipy python-git python-pip ipython 
$ sudo apt install libtbb-dev libblas-dev liblapack-dev python-catkin-tools libv4l-dev 
$ sudo apt install build-essential python-dev libxml2 libxml2-dev zlib1g-dev bison flex libigraph0-dev texlive-binaries
$ sudo pip install -i https://pypi.tuna.tsinghua.edu.cn/simple python-igraph
$ sudo pip install python-igraph --upgrade

2、编译Kaibr

$ cd ~/kalibr_ws/src
$ git clone https://github.com/ethz-asl/Kalibr.git
$ cd .. && catkin build -DCMAKE_BUILD_TYPE=Release -j2

使用方式

$ rosrun kalibr <command_you_want_to_run_here>

例如:查看标定板生成的指令的参数

$ rosrun kalibr kalibr_create_target_pdf -h

usage:
Example Aprilgrid:
kalibr_create_target_pdf --type apriltag --nx 6 --ny 6 --tsize 0.08 --tspace 0.3
Example Checkerboard:
kalibr_create_target_pdf --type checkerboard --nx 6 --ny 6 -csx 0.05 --csy 0.1

Generate PDFs of calibration patterns.

optional arguments:
-h, --help show this help message and exit

Output options:
output Output filename
–eps Also output an EPS file

Generic grid options:
–type GRIDTYPE The grid pattern type. (‘apriltag’ or ‘checkerboard’)
–nx N_COLS The number of tags in x direction (default: 6)
–ny N_ROWS The number of tags in y direction (default: 7)

Apriltag arguments:
–tsize TSIZE The size of one tag [m] (default: 0.08)
–tspace TAGSPACING The space between the tags in fraction of the edge size [0…1] (default: 0.3)
–tfam TAGFAMILIY Familiy of April tags [‘t16h5’, ‘t25h7’, ‘t25h9’, ‘t36h11’] (default: t36h11)
–skip-ids SKIPIDS Space-separated list of tag ids to leave blank (default: none)

Checkerboard arguments:
–csx CHESSSZX The size of one chessboard square in x direction [m] (default: 0.05)
–csy CHESSSZY The size of one chessboard square in y direction [m] (default: 0.05)

3、制作标定板

下载标定板

三种类型的标定板(Aprilgrid, Checkerboard, Circlegrid)。由于Aprilgrid能提供序号信息, 能够防止姿态计算时出现跳跃的情况, 所以建议采用Aprilgrid进行标定。

标定板下载:https://github.com/ethz-asl/kalibr/wiki/downloads

image-20220821173428574

对于针孔型相机 pinhole,失真模型分为为plumb_bob和rational_polynomial,具体取决于使用的径向畸变参数K的数量,当K为6时是rational_polynomial模型,其他则为plumb_bob。

生成标定板

$ rosrun kalibr kalibr_create_target_pdf --type apriltag --nx 6 --ny 6 --tsize 0.08 --tspace 0.3

这时文件夹中会生成一个标定板 target.pdf

image-20220914222047104

注意:这个是A0纸尺寸的,后面我们编写target.yaml文件的时候要以实际的标定板的尺寸进行参数填写

target.yaml文件

在标定之间我们需要一个描述这个标定板的文件,这个文件是描述标定板的真实尺度的,比如:如果用A4纸打印的就写成如下即可

target_type: 'aprilgrid' #gridtype
tagCols: 6               #number of apriltags
tagRows: 6               #number of apriltags
tagSize: 0.021           #size of apriltag, edge to edge [m]
tagSpacing: 0.285714285714   #ratio of space between tags to tagSize
codeOffset: 0            #code offset for the first tag in the aprilboard

4、数据采集

把标定纸放在桌面上,让相机从各个角度对标定纸进行拍摄即可,或者相机不动,把标定纸在相机前面晃,让相机能在各个角度对标定纸拍摄

image-20220915211550249

通过rosbag record来进行话题的录制即可

注意:通常设备采集的频率为 20-60 hz, 这会使得标定的图像过多, 而导致计算量太大。 最好通过topic_tools将ros topic的频率降低到4hz左右进行采集

$ roslaunch zed_wrapper zed2i.launch
$ rosrun topic_tools throttle messages /zed2i/zed_node/right_raw/image_raw_color 4.0 /right/image_raw
$ rosrun topic_tools throttle messages /zed2i/zed_node/left_raw/image_raw_color 4.0 /left/image_raw
$ rosbag record -O camera_calibra.bag /right/image_raw /left/image_raw

image-20220915212336843

我这里录制了一小段的bag

image-20220915212438277

5、相机标定

kalibr_calibrate_cameras的命令格式,他可以实现多相机标定

$ rosrun kalibr kalibr_calibrate_cameras --bag [filename.bag] --topics [TOPIC_0 ... TOPIC_N] --models [MODEL_0 ... MODEL_N] --target [target.yaml]

相机的models

Camera models
Kalibr supports the following projection models:

pinhole camera model (pinhole)
(intrinsics vector: [fu fv pu pv])
omnidirectional camera model (omni)
(intrinsics vector: [xi fu fv pu pv])
double sphere camera model (ds)
(intrinsics vector: [xi alpha fu fv pu pv])
extended unified camera model (eucm)
(intrinsics vector: [alpha beta fu fv pu pv])
The intrinsics vector contains all parameters for the model:

fu, fv: focal-length
pu, pv: principal point
xi: mirror parameter (only omni)
xi, alpha: double sphere model parameters (only ds)
alpha, beta: extended unified model parameters (only eucm)
Distortion models
Kalibr supports the following distortion models:

radial-tangential (radtan)
(distortion_coeffs: [k1 k2 r1 r2])
equidistant (equi)
(distortion_coeffs: [k1 k2 k3 k4])
fov (fov)
(distortion_coeffs: [w])
none (none)
(distortion_coeffs: [])

pinhole-equi 模型,对畸变大的相机效果不错

标定中遇到的问题

问题1:

Initialization of focal length failed. You can enable manual input by setting ‘KALIBR_MANUAL_FOCAL_LENGTH_INIT’.

image-20220915221133561

解决办法:终端中设置变量 KALIBR_MANUAL_FOCAL_LENGTH_INIT = 1 然后程序运行时手动给相机设置初始焦距

$ export KALIBR_MANUAL_FOCAL_LENGTH_INIT=1

image-20220915221701521

问题2

Cameras are not connected through mutual observations, please check the dataset. Maybe adjust the approx. sync. tolerance.

image-20220915222413470

解决办法:Kalibr官网的issue中找到了一个解决办法,注释掉Kalibr/aslam_offline_calibration/kalibr/python/kalibr_calibrate_cameras中的一段代码

image-20220915222303597

标定结果查看

标定完成后会生成3个文件

image-20220915231818842

pdf中有一些误差分析结果

image-20220915231523921

从给出的结果来看,重投影误差不大,基本控制在1-2个像素之内。

image-20220915232033754

标定结果和相机本身的/camera/color/camera_info话题中读出来的基本一致,可见标定效果还行。

6、相机-IMU外参标定

联合标定需要的材料:

1、数据包 xxx.bag: 里面包含了相机和IMU的话题

2、IMU描述文件[imu.yaml]: 描述IMU的噪声模型

3、相机的描述文件[camchain.yaml]: 相机的内参和外参

4、标定板描述文件[target.yaml]:描述标定板的真实尺寸

注意:收集数据的过程中充分激励IMU的各个轴,也要注意别运动太剧烈,保证图像不模糊,采集数据的最佳频率为图像20Hz, IMU 200 Hz

收集数据

# 修改三个话题的发布频率
$ rosrun topic_tools throttle messages /zed2i/zed_node/right_raw/image_raw_color 20.0 /right/image_raw
$ rosrun topic_tools throttle messages /zed2i/zed_node/left_raw/image_raw_color 20.0 /left/image_raw
$ rosrun topic_tools throttle messages /zed2i/zed_node/imu/data_raw 200.0 /imu/data_raw
# 录制数据
$ rosbag record -O stereo-imu-calibrate.bag /right/image_raw /left/image_raw /imu/data_raw

image-20220916094756754

标定

kalibr_calibrate_imu_camera 命令格式

$ rosrun kalibr kalibr_calibrate_imu_camera --target [target.yaml] --cam [camchain.yaml] --imu [imu.yaml] --bag [dynamic.bag] --show-extraction

kalibr_calibrate_imu_camera的可输入参数

Calibrate the spatial and temporal parameters of an IMU to a camera chain.

usage:
Example usage to calibrate a camera system against an IMU using an aprilgrid.
Temporal calibration is enabled by default.

kalibr_calibrate_imu_camera --bag MYROSBAG.bag --cam camchain.yaml --imu imu.yaml \
         --target aprilgrid.yaml

camchain.yaml: is the camera-system calibration output of the multiple-camera
               calibratin tool (kalibr_calibrate_cameras)

example aprilgrid.yaml:       |  example imu.yaml: (ADIS16448)
    target_type: 'aprilgrid'  |      accelerometer_noise_density: 0.006
    tagCols: 6                |      accelerometer_random_walk: 0.0002
    tagRows: 6                |      gyroscope_noise_density: 0.0004
    tagSize: 0.088            |      gyroscope_random_walk: 4.0e-06
    tagSpacing: 0.3           |      update_rate: 200.0

optional arguments:
-h, --help show this help message and exit

Dataset source:
–bag BAGFILE Ros bag file containing image and imu data (rostopics specified in the yamls)
–bag-from-to bag_from_to bag_from_to
Use the bag data starting from up to this time [s]
–bag-freq bag_freq Frequency to extract features at [hz]
–perform-synchronization
Perform a clock synchronization according to ‘Clock synchronization algorithms for network
measurements’ by Zhang et al. (2002).

Camera system configuration:
–cams CHAIN_YAML Camera system configuration as yaml file
–recompute-camera-chain-extrinsics
Recompute the camera chain extrinsics. This option is exclusively recommended for debugging
purposes in order to identify problems with the camera chain extrinsics.
–reprojection-sigma REPROJECTION_SIGMA
Standard deviation of the distribution of reprojected corner points [px]. (default: 1.0)

IMU configuration:
–imu IMU_YAMLS [IMU_YAMLS …]
Yaml files holding the IMU noise parameters. The first IMU will be the reference IMU.
–imu-delay-by-correlation
Estimate the delay between multiple IMUs by correlation. By default, no temporal calibration
between IMUs will be performed.
–imu-models IMU_MODELS [IMU_MODELS …]
The IMU models to estimate. Currently supported are ‘calibrated’, ‘scale-misalignment’ and
‘scale-misalignment-size-effect’.

Calibration target:
–target TARGET_YAML Calibration target configuration as yaml file

Optimization options:
–no-time-calibration
Disable the temporal calibration
–max-iter MAX_ITER Max. iterations (default: 30)
–recover-covariance Recover the covariance of the design variables.
–timeoffset-padding TIMEOFFSET_PADDING
Maximum range in which the timeoffset may change during estimation [s] (default: 0.03)

Output options:
–show-extraction Show the calibration target extraction. (disables plots)
–extraction-stepping
Show each image during calibration target extraction (disables plots)
–verbose Verbose output (disables plots)
–dont-show-report Do not show the report on screen after calibration.
–export-poses Also export the optimized poses.

关于IMU的描述文件如下,新建一个imu_param.yaml文件,写入如下内容

rostopic: /zed2i/zed_node/imu/data_raw
update_rate: 200.0 #Hz

accelerometer_noise_density: 1.4630115150562858e-02
accelerometer_random_walk: 4.5775365120985598e-04
gyroscope_noise_density: 1.1732970626561320e-03
gyroscope_random_walk: 3.1396269201840859e-06

然后运行标定命令如下:

$ ZED_calib rosrun kalibr kalibr_calibrate_imu_camera --bag ./dataSet/stereo-imu-calibrate.bag --target target.yaml --cam camera_calibra-camchain.yaml --imu imu_param.yaml

如果采集的数据包事件比较长,那么标定的事件相对也比较长,因为里面涉及到大规模超定方程的求解。我这里采集的数据包大概有1.7G左右,正在优化中,如下图

image-20220916210151407

标定结果

image-20220916224831513

最后标定成功会弹出一个窗口,里面有一些误差分析报告的图

image-20220916223300158

还有生成的一些文件

image-20220916225128591

image-20220916225318053

相机的外参和内参已经标定完成,后面用这个ZED 2i以及外参和内参跑一下vSLAM相关的框架!

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

ZED 2i 双目-IMU标定 的相关文章

  • ROS2+cartographer+激光雷达+IMU里程计数据融合(robot_locazation) 建图

    目录 写在前面总体流程分块解释IMU数据接收和发布车轮编码器数据接收和发布数据融合 robot localization概括使用 cartographer订阅 效果 写在前面 之前写了一篇ROS2 43 cartorgrapher 43 激
  • Ubuntu18.04+ZED SDK安装+ZED Python API+zed ros wrapper安装 手把手详细教程

    1 安装前准备 1 ubuntu显卡驱动要有 xff0c 没有的可以搜索如何安装ubuntu显卡驱动 xff0c 教程很多 xff0c 这里不再详细说明 2 ROS需要提前安装好 xff0c 可以搜索ubuntu如何安装ROS 我这里安装的
  • Kalibr 之 Camera-IMU 标定 (总结)

    Overview 欢迎访问 持续更新 xff1a https cgabc xyz posts db22c2e6 ethz asl kalibr is a toolbox that solves the following calibrati
  • ROS2中IMU话题的发布及可视化

    环境 xff1a Ubuntu 20 04 xff0c ROS2 Foxy 传感器 xff1a 维特智能BWT901CL 代码是从维特智能的示例代码修改的 xff0c 实现基本的加速度 角速度和角度读取 xff0c 发布IMU消息 这个传感
  • VINS(七)estimator_node 数据对齐 imu预积分 vision

    首先通过vins estimator mode监听几个Topic xff08 频率2000Hz xff09 xff0c 将imu数据 xff0c feature数据 xff0c raw image数据 xff08 用于回环检测 xff09
  • ORB-SLAM3:单目+imu 详细代码解读

    输入文件 Examples Monocular Inertial mono inertial euroc Vocabulary ORBvoc txt Examples Monocular Inertial EuRoC yaml 存储相机 i
  • ubuntu18配置ZED+ros

    ubuntu18配置ZED 43 ros 1 安装nvidia显卡驱动 查看适配自己显卡的驱动 ubuntu drivers devices 选择recommended版本的驱动 span class token function sudo
  • MAG02 IMU传感器模块替代MPU6050模块介绍

    MAG02模块内置TDK高精度6轴IMU 惯性测量单元 xff09 传感器芯片 xff0c 通过处理器读取传感器数据 xff0c 并经过内部复杂运算后通过串口输出加速度 xff0c 角速度 xff0c 角度等数据 xff0c 大大减轻了用户
  • 飞控IMU数据进阶处理(FFT,滤波器)

    前面的文章 xff08 知乎专栏 https zhuanlan zhihu com c 60591778 xff09 曾简单讲过IMU数据 xff08 陀螺仪 加速度数据 xff09 的校准以及一阶低通滤波 本文在此基础上更进一步讲一下数据
  • IMU校正以及姿态融合

    本文为博主 声时刻 原创文章 xff0c 未经博主允许不得转载 联系方式 xff1a shenshikexmu 64 163 com 缘起 有缘在简极科技兼职两年 接触了IMU xff0c 我去的时候那家公司还是一个要把IMU放进足球的公司
  • vins中imu融合_VINS代码解读

    VINS estimator 摘抄 我们初始化的原因是单目惯性紧耦合系统是一个非线性程度很高的系统 xff0c 首先单目是无法获得空间中的绝对尺度 xff0c 而IMU又必然存在偏置 xff0c 在后面进行求解的时候还需要用到重力加速度 包
  • IMU 测量模型和运动学模型

    一 概念 高斯白噪声 测量噪声是AD转换器件引起的外部噪声 xff0c 波动激烈的测量白噪声 随机游走 这里指零偏Bias 随机游走噪声 xff0c 是传感器内部机械 温度等各种物理因素产生的传感器内部误差的综合参数 xff0c 是变化缓慢
  • vins-fusion代码解读[五] imu在vins里的理解

    SLAM新手 xff0c 欢迎讨论 IMU作用 vins中 xff0c IMU只读取IMU六轴的信息 xff0c 3轴线加速度 xff08 加速度计 xff09 和3轴角速度 xff08 陀螺仪 xff09 通过对陀螺仪的一次积分 xff0
  • Kalibr进行相机-IMU联合标定踩坑记录RuntimeError: Optimization failed!

    1 具体标定步骤 xff0c 跟网上别的一模一样 xff0c 此处就不列举 2 记录踩坑过程 xff1a RuntimeError Optimization failed 当执行到开始联合标定时 xff0c 也就是如下指令 xff1a ka
  • 【ZED】从零开始使用ZED相机(二):打开相机+捕获图像

    引言 关于ZED相机的安装和配置可以先参考 ZED 从零开始使用ZED相机 xff08 一 xff09 xff1a windows下的安装配置与测试 xff0c 接下来开始二次开发ZED相机 阅读ZED API文档 xff0c 选择自己使用
  • 使用zed摄像头跑ORB_SLAM2

    zed ros wrapper安装 首先对zed ros wrapper安装 xff1a 具体操作步骤及代码的参考链接 xff1a https github com stereolabs zed ros wrapper git mkdir
  • cartographer 处理IMU(激光,里程计等)流程

    1 cartographer ros 入口文件 node main cc 入口函数main 如下图 ros init argc argv cartographer node ros start cartographer ros Scoped
  • win10安装ZED Python API以及解决python get_python_api.py报错

    Python 安装脚本位于 C Program Files x86 ZED SDK 中 运行如下命令 cd C Program Files x86 ZED SDK python get python api py 此时若出现如下报错 解决方
  • IMU-Allan方差分析

    使用Allan方差来确定MEMS陀螺仪的噪声参数 陀螺仪测量模型为 使用长时间静止的陀螺仪数据对陀螺仪噪声参数进行分析 上式中 三个噪声参数N 角度随机游走 K 速率随机游走 和B 偏差不稳定性 背景 Allan方差最初由David W A
  • An Introduction for IMU 2 - IMU数据融合与姿态解算

    在上一篇博客中 我们已经介绍了IMU的内部工作原理 以及如何通过Arduino读取MPU6050的数据 虽然可以从DMP直接读取姿态角 但其数据返回的频率相对较低 同时由于DMP库不是开源的 其内部的工作原理 输出姿态角的准确性都不清楚 而

随机推荐

  • 2.Open3D教程——文件读取和保存

    文件读取和保存 本教程演示了Open3D如何读写基本数据结构 1 点云 下面的代码读取和写入点云 span class token keyword print span span class token punctuation span s
  • 7.Open3D教程——表面重建

    在许多情况下 xff0c 我们希望生成密集的三维几何体 xff0c 即三角形网格 然而 xff0c 从多视点立体方法 xff0c 或深度传感器 xff0c 我们只能获得一个非结构化的点云 为了从非结构化输入中得到三角形网格 xff0c 我们
  • PASCAL VOC数据集

    一 简介 PASCAL pattern analysis statistical modelling and computational learning VOC visual object classes 该挑战赛的竞赛项目主要包括 图像
  • ubuntu python 通过奥比中光摄像头获取深度图片和彩色图片

    1 依赖 安装Openni Openni下载Openni添加至环境 xff08 要通过全局变量找到Openni头文件和库 xff09 安装primesense和openni pip install primesense pip instal
  • ROS tf使用报错:ImportError: dynamic module does not define module export function (PyInit__tf2)

    1 报错内容 Traceback span class token punctuation span most recent call last span class token punctuation span File span cla
  • ubuntu cuda cudnn tensorRT的卸载和安装

    1 安装显卡驱动 显卡安装教程 查看N卡驱动支持的最高cuda版本 nvidia smi 2 卸载 span class token function sudo span span class token function apt get
  • 初识VSCode

    Visual Studio Code xff08 以下简称vscode xff09 是一个轻量且强大的代码编辑器 xff0c 跨平台支持Windows xff0c Mac OS X和Linux 内置JavaScript TypeScript
  • Modbus通信及数据存储读取

    1 存储区代号 代码号功能1区输入线圈0区输出线圈3区输入寄存器4区输出寄存器 2 功能码 代码功能0x01读取输出线圈0x02读取输入线圈0x03读取输出寄存器0x04读取输入寄存器0x05写入单个线圈0x06写入单个寄存器0x0F写入多
  • 着色器语言 GLSL (opengl-shader-language)入门大全

    GLSL 中文手册 基本类型 类型说明void空类型 即不返回任何值bool布尔类型 true falseint带符号的整数 signed integerfloat带符号的浮点数 floating scalarvec2 vec3 vec4n
  • Data structure alignment (数据结构对齐 / 内存对齐)

    开篇的话 在比较老的编译器里 xff0c 如果没有对变量取地址的操作 xff0c 那么有些局部变量是通过寄存器保存的 xff0c 不占栈上内存 xff0c 根本不存在内存中如何排列的问题 xff0c 比如TurboC 2 0这种 在一些较新
  • C++primer plus和C++ primer的读书心得

    C 43 43 两本巨著primer plus和primer太过于经典 xff0c 以至于读过多次 xff0c 每次阅读仍然有新的收获 xff0c 所以将一些零碎的知识点整理在这里 xff0c 与大家共同进步 1 i 43 43 与 43
  • VINS 外参在线标定

    在VINS中相机的外参 R i c R ic R i c 是可以在线动态标定的 xff0c 实现函数为 xff1a 6
  • A-LOAM源码阅读

    LOAM 论文地址 xff1a https www ri cmu edu pub files 2014 7 Ji LidarMapping RSS2014 v8 pdf A LOAM地址 xff1a https github com HKU
  • LeGo-LOAM 跑通与源码学习

    论文链接 xff1a https www researchgate net LeGO LOAM 源码仓库 xff1a https github com RobustFieldAutonomyLab LeGO LOAM 本人注释 xff1a
  • SLAM中evo评估工具(用自己的数据集评估vinsFusion)

    目录 xff1a 配置标题文件修改源码修改第一处第二处第三处重新编译工程 安装evo1 安装命令2 常用指令 运行vinsFusion生成位姿估计文件使用evo评估轨迹 配置标题文件修改 主要根据自己的设备 xff0c 修改自己传感器的RO
  • Ubuntu中USB端口与外设绑定,ROS读取IMU模块数据

    目录 xff1a 1 根据设备ID绑定1 1 查看ID1 2 编写USB规则文件1 3 查看绑定结果 2 根据电脑USB口绑定2 1 找到USB端口名称2 2 编写绑定规则 3 通过ROS读数据 1 根据设备ID绑定 方法原理 xff1a
  • 实现外网Ping通WSL(网卡桥接方式实现)

    目录 xff1a 前言 xff1a 实现原理 xff1a 实现步骤1 开启hyper v2 编写桥接网络powershell脚本3 编写网络配置脚本 实现结果取消桥接最后 前言 xff1a 在我们经常和机器人打交道的这群人中有一个需求 xf
  • 如何在markdown中插入表情包

    我们平时经常使用markdown完成一些诸如博客的文档写作 xff0c 但是有时像我这种语言比较乏力的急需要在文档写作过程中插入表情包来完整的表达我想要表达的意思 xff0c 所以我去网上查了一下 xff0c 还真有 比如我想要表达开心即s
  • ROS多设备组网(WSL+miniPC+Nv Orin)

    目录 xff1a 前言硬件连接组网配置1 获取hostname和IP2 在主机添加从机的host信息3 在从机1中配置4 在从机2中配置 测试test1 话题订阅test2 rqt plot可视化传感器信息 最后 前言 实验室最近购买了两台
  • ZED 2i 双目-IMU标定

    目录 xff1a 前言IMU标定1 编译标定工具2 准备数据集3 标定 Camera IMU标定1 安装依赖2 编译Kaibr3 制作标定板下载标定板生成标定板target yaml文件 4 数据采集5 相机标定标定中遇到的问题问题1 xf