aruco板_基于arucoTag的简单slam

2023-05-16

#include

#include

#include

#include

#include

#include

#include

#include

#include

#include

#include

#include

#include "g2o/types/slam3d/types_slam3d.h"

#include "g2o/types/slam3d/vertex_pointxyz.h"

#include "g2o/types/slam3d/vertex_se3.h"

#include "g2o/types/slam3d/edge_se3.h"

#include "g2o/types/slam3d/edge_se3_pointxyz.h"

#include "g2o/core/factory.h"

#include "g2o/core/optimization_algorithm_factory.h"

#include "g2o/core/sparse_optimizer.h"

#include "g2o/core/block_solver.h"

#include "g2o/solvers/dense/linear_solver_dense.h"

#include "g2o/core/optimization_algorithm_levenberg.h"

#include "icp_g2o.hpp"

using namespace std;

using namespace cv;

using namespace Eigen;

using namespace g2o;

//使用图片

//输入当前帧检测到的tag

//维护一张节点地图用于g2o

class ArucoFrame

{

public:

vector landmark_id;

vector<:vector3d> landmarks_pointXYZ;//在相机坐标系下的位置

Eigen::Isometry3d robot_pose;//在map坐标系下的位姿

};

class ArucoMap

{

public:

vector landmark_id;

vector<:vector3d> landmarks_pointXYZ;//在Map坐标系下的位置

};

ArucoMap ArucoMapGlobal;

vector ArucoFrameGlobal;

int id_vertex_pose=0, id_vertex_pointXYZ_start=100;//机器人pose的初始点认为是建图坐标系原点,id从0开始,tag的节点id从100开始。默认机器人pose不可能超过100个

void buildMap(vector< int > &ids, vector< vector< Point2f > > &corners, vector< Vec3d > &rvecs, vector< Vec3d > &tvecs, g2o::SparseOptimizer &optimizer)

{

//获取当前帧里的tag

ArucoFrame ArucoFrame_temp;

if(ids.size() != 0)

{

ArucoFrame_temp.robot_pose = Eigen::Isometry3d::Identity();

for(int i=0; i

{

ArucoFrame_temp.landmark_id.push_back(ids[i]);

//cv转换到eigen下

Mat rot_mat;

Rodrigues(rvecs[i], rot_mat);

Eigen::Matrix3d eigen_r;

Eigen::Vector3d eigen_t;

cv2eigen(rot_mat, eigen_r);

cv2eigen(tvecs[i],eigen_t);

//这里的rt对应的T是从mark坐标系变到相机坐标系

//Point_camera = T_camera-mark * Point_mark

//很重要!!所以这里的四个点是按mark坐标系下的顺序排列的

ArucoFrame_temp.landmarks_pointXYZ.push_back( eigen_r * Eigen::Vector3d(-0.03,0.03,0)+eigen_t );

ArucoFrame_temp.landmarks_pointXYZ.push_back( eigen_r * Eigen::Vector3d(0.03,0.03,0)+eigen_t );

ArucoFrame_temp.landmarks_pointXYZ.push_back( eigen_r * Eigen::Vector3d(0.03,-0.03,0)+eigen_t );

ArucoFrame_temp.landmarks_pointXYZ.push_back( eigen_r * Eigen::Vector3d(-0.03,-0.03,0)+eigen_t );

}

ArucoFrameGlobal.push_back(ArucoFrame_temp);

}

else

return ;

//对地图操作

if(ArucoMapGlobal.landmark_id.size() == 0)//初始化第一帧

{

for(int i=0; i

{

ArucoMapGlobal.landmark_id.push_back(ArucoFrame_temp.landmark_id[i]);

ArucoMapGlobal.landmarks_pointXYZ.push_back(ArucoFrame_temp.landmarks_pointXYZ[i*4+0]);

ArucoMapGlobal.landmarks_pointXYZ.push_back(ArucoFrame_temp.landmarks_pointXYZ[i*4+1]);

ArucoMapGlobal.landmarks_pointXYZ.push_back(ArucoFrame_temp.landmarks_pointXYZ[i*4+2]);

ArucoMapGlobal.landmarks_pointXYZ.push_back(ArucoFrame_temp.landmarks_pointXYZ[i*4+3]);

//添加pose

VertexSE3* v = new VertexSE3;

v->setEstimate(ArucoFrame_temp.robot_pose);

v->setId(id_vertex_pose++);

optimizer.addVertex(v);

//添加landmark和edge

for(int j=0; j<4; j++)

{

VertexPointXYZ* l = new VertexPointXYZ;

l->setEstimate(ArucoFrame_temp.landmarks_pointXYZ[i*4+j]);

l->setFixed(true);

l->setId(id_vertex_pointXYZ_start+ArucoFrame_temp.landmark_id[i]*4+j);//之所以直接用tag的id是因为不会存在相同的tag,因此vertex的序号不会出现一样的。

optimizer.addVertex(l);

EdgeSE3PointXYZ* e = new EdgeSE3PointXYZ;

e->setVertex(0, (optimizer.vertices().find(id_vertex_pose-1))->second);

e->setVertex(1, (optimizer.vertices().find(id_vertex_pointXYZ_start+ArucoFrame_temp.landmark_id[i]*4+j))->second);

e->setMeasurement(ArucoFrame_temp.landmarks_pointXYZ[i*4+0]);

e->setParameterId(0,0);//这句话必须加

optimizer.addEdge(e);

}

}

}

else

{

//寻找当前帧里的tagid是否和map里的id一样

vector id_same, id_different;

for(int i=0; i

{

int j;

for(j=0; j

{

if(ArucoMapGlobal.landmark_id[j] == ArucoFrame_temp.landmark_id[i])

{

id_same.push_back(i);

break;

}

}

if(j == ArucoMapGlobal.landmark_id.size())

id_different.push_back(i);

}

if(id_different.size() != 0)//如果有新的id能看到,就要添加进地图里

{

if(id_same.size() != 0)//必须要同时看到地图里存在的tag以及新的tag,才能将新的tag添加进地图中,因为是根据scan匹配map获得自身位资

{

//先根据icp匹配获得当前帧的位置。

vector<:vector3d> landmarkXYZ_common_map;

vector<:vector3d> landmarkXYZ_common_frame;

for(int i=0; i

{

for(int j=0; j

{

if(ArucoMapGlobal.landmark_id[i] == ArucoFrame_temp.landmark_id[id_same[j]])

{

landmarkXYZ_common_map.push_back(ArucoMapGlobal.landmarks_pointXYZ[i*4+0]);

landmarkXYZ_common_map.push_back(ArucoMapGlobal.landmarks_pointXYZ[i*4+1]);

landmarkXYZ_common_map.push_back(ArucoMapGlobal.landmarks_pointXYZ[i*4+2]);

landmarkXYZ_common_map.push_back(ArucoMapGlobal.landmarks_pointXYZ[i*4+3]);

landmarkXYZ_common_frame.push_back(ArucoFrame_temp.landmarks_pointXYZ[id_same[j]*4+0]);

landmarkXYZ_common_frame.push_back(ArucoFrame_temp.landmarks_pointXYZ[id_same[j]*4+1]);

landmarkXYZ_common_frame.push_back(ArucoFrame_temp.landmarks_pointXYZ[id_same[j]*4+2]);

landmarkXYZ_common_frame.push_back(ArucoFrame_temp.landmarks_pointXYZ[id_same[j]*4+3]);

break;

}

}

}

Eigen::Isometry3d T;

bundleAdjustment(landmarkXYZ_common_map, landmarkXYZ_common_frame, T);//这个T就是当前摄像头的pose

ArucoFrame_temp.robot_pose = T;

ArucoFrameGlobal.back().robot_pose = T;

//当前摄像头的位姿计算出来以后,更新map中的pose和edge,这一步没有landmark添加进来

VertexSE3* v = new VertexSE3;

v->setEstimate(ArucoFrame_temp.robot_pose);

v->setId(id_vertex_pose++);

optimizer.addVertex(v);

for(int i=0; i

{

for(int j=0; j<4; j++)

{

EdgeSE3PointXYZ* e = new EdgeSE3PointXYZ;

e->setVertex(0, (optimizer.vertices().find(id_vertex_pose-1))->second);

e->setVertex(1, (optimizer.vertices().find(id_vertex_pointXYZ_start+ArucoFrame_temp.landmark_id[id_same[i]]*4+j))->second);

e->setMeasurement(ArucoFrame_temp.landmarks_pointXYZ[id_same[i]*4+j]);

e->setParameterId(0,0);//这句话必须加

optimizer.addEdge(e);

}

}

//更新map中的landmark和edge

for(int i=0; i

{

ArucoMapGlobal.landmark_id.push_back(ArucoFrame_temp.landmark_id[id_different[i]]);

ArucoMapGlobal.landmarks_pointXYZ.push_back(T * ArucoFrame_temp.landmarks_pointXYZ[id_different[i]*4+0]);

ArucoMapGlobal.landmarks_pointXYZ.push_back(T * ArucoFrame_temp.landmarks_pointXYZ[id_different[i]*4+1]);

ArucoMapGlobal.landmarks_pointXYZ.push_back(T * ArucoFrame_temp.landmarks_pointXYZ[id_different[i]*4+2]);

ArucoMapGlobal.landmarks_pointXYZ.push_back(T * ArucoFrame_temp.landmarks_pointXYZ[id_different[i]*4+3]);

for(int j=0; j<4; j++)

{

VertexPointXYZ* l = new VertexPointXYZ;

l->setEstimate(T * ArucoFrame_temp.landmarks_pointXYZ[id_different[i]*4+j]);

l->setId(id_vertex_pointXYZ_start+ArucoFrame_temp.landmark_id[id_different[i]]*4+j);

optimizer.addVertex(l);

EdgeSE3PointXYZ* e = new EdgeSE3PointXYZ;

e->setVertex(0, (optimizer.vertices().find(id_vertex_pose-1))->second);

e->setVertex(1, (optimizer.vertices().find(id_vertex_pointXYZ_start+ArucoFrame_temp.landmark_id[id_different[i]]*4+j))->second);

e->setMeasurement(ArucoFrame_temp.landmarks_pointXYZ[id_different[i]*4+j]);

e->setParameterId(0,0);//这句话必须加

optimizer.addEdge(e);

}

}

}

}

else//如果看到的全是存在的tag就添加优化关系

{

vector id_same;

for(int i=0; i

{

int j;

for(j=0; j

{

if(ArucoMapGlobal.landmark_id[j] == ArucoFrame_temp.landmark_id[i])

{

id_same.push_back(i);

break;

}

}

}

//先根据icp匹配获得当前帧的位置。

vector<:vector3d> landmarkXYZ_common_map;

vector<:vector3d> landmarkXYZ_common_frame;

for(int i=0; i

for(int j=0; j

{

if(ArucoMapGlobal.landmark_id[i] == ArucoFrame_temp.landmark_id[id_same[j]])

{

landmarkXYZ_common_map.push_back(ArucoMapGlobal.landmarks_pointXYZ[i*4+0]);

landmarkXYZ_common_map.push_back(ArucoMapGlobal.landmarks_pointXYZ[i*4+1]);

landmarkXYZ_common_map.push_back(ArucoMapGlobal.landmarks_pointXYZ[i*4+2]);

landmarkXYZ_common_map.push_back(ArucoMapGlobal.landmarks_pointXYZ[i*4+3]);

landmarkXYZ_common_frame.push_back(ArucoFrame_temp.landmarks_pointXYZ[id_same[j]*4+0]);

landmarkXYZ_common_frame.push_back(ArucoFrame_temp.landmarks_pointXYZ[id_same[j]*4+1]);

landmarkXYZ_common_frame.push_back(ArucoFrame_temp.landmarks_pointXYZ[id_same[j]*4+2]);

landmarkXYZ_common_frame.push_back(ArucoFrame_temp.landmarks_pointXYZ[id_same[j]*4+3]);

break;

}

}

Eigen::Isometry3d T;

bundleAdjustment(landmarkXYZ_common_map, landmarkXYZ_common_frame, T);//这个T就是当前摄像头的pose

ArucoFrame_temp.robot_pose = T;

ArucoFrameGlobal.back().robot_pose = T;

VertexSE3* v = new VertexSE3;

v->setEstimate(ArucoFrame_temp.robot_pose);

v->setId(id_vertex_pose++);

optimizer.addVertex(v);

for(int i=0; i

{

for(int j=0; j<4; j++)

{

EdgeSE3PointXYZ* e = new EdgeSE3PointXYZ;

e->setVertex(0, (optimizer.vertices().find(id_vertex_pose-1))->second);

e->setVertex(1, (optimizer.vertices().find(id_vertex_pointXYZ_start+ArucoFrame_temp.landmark_id[id_same[i]]*4+j))->second);

e->setMeasurement(ArucoFrame_temp.landmarks_pointXYZ[id_same[i]*4+j]);

e->setParameterId(0,0);//这句话必须加

optimizer.addEdge(e);

}

}

}

}

}

namespace {

const char* about = "Basic marker detection";

const char* keys =

"{d | 0 | dictionary: DICT_4X4_50=0, DICT_4X4_100=1, DICT_4X4_250=2,"

"DICT_4X4_1000=3, DICT_5X5_50=4, DICT_5X5_100=5, DICT_5X5_250=6, DICT_5X5_1000=7, "

"DICT_6X6_50=8, DICT_6X6_100=9, DICT_6X6_250=10, DICT_6X6_1000=11, DICT_7X7_50=12,"

"DICT_7X7_100=13, DICT_7X7_250=14, DICT_7X7_1000=15, DICT_ARUCO_ORIGINAL = 16}"

"{v | | Input from video file, if ommited, input comes from camera }"

"{ci | 0 | Camera id if input doesnt come from video (-v) }"

"{c | log270 | Camera intrinsic parameters. Needed for camera pose }"

"{l | 0.06 | Marker side lenght (in meters). Needed for correct scale in camera pose }"

"{dp | detector_params.yml | File of marker detector parameters }"

"{r | | show rejected candidates too }";

}

static bool readCameraParameters(string filename, Mat &camMatrix, Mat &distCoeffs) {

FileStorage fs(filename, FileStorage::READ);

if(!fs.isOpened())

return false;

fs["camera_matrix"] >> camMatrix;

fs["distortion_coefficients"] >> distCoeffs;

return true;

}

static bool readDetectorParameters(string filename, Ptr<:detectorparameters> &params) {

FileStorage fs(filename, FileStorage::READ);

if(!fs.isOpened())

return false;

fs["adaptiveThreshWinSizeMin"] >> params->adaptiveThreshWinSizeMin;

fs["adaptiveThreshWinSizeMax"] >> params->adaptiveThreshWinSizeMax;

fs["adaptiveThreshWinSizeStep"] >> params->adaptiveThreshWinSizeStep;

fs["adaptiveThreshConstant"] >> params->adaptiveThreshConstant;

fs["minMarkerPerimeterRate"] >> params->minMarkerPerimeterRate;

fs["maxMarkerPerimeterRate"] >> params->maxMarkerPerimeterRate;

fs["polygonalApproxAccuracyRate"] >> params->polygonalApproxAccuracyRate;

fs["minCornerDistanceRate"] >> params->minCornerDistanceRate;

fs["minDistanceToBorder"] >> params->minDistanceToBorder;

fs["minMarkerDistanceRate"] >> params->minMarkerDistanceRate;

fs["doCornerRefinement"] >> params->doCornerRefinement;

fs["cornerRefinementWinSize"] >> params->cornerRefinementWinSize;

fs["cornerRefinementMaxIterations"] >> params->cornerRefinementMaxIterations;

fs["cornerRefinementMinAccuracy"] >> params->cornerRefinementMinAccuracy;

fs["markerBorderBits"] >> params->markerBorderBits;

fs["perspectiveRemovePixelPerCell"] >> params->perspectiveRemovePixelPerCell;

fs["perspectiveRemoveIgnoredMarginPerCell"] >> params->perspectiveRemoveIgnoredMarginPerCell;

fs["maxErroneousBitsInBorderRate"] >> params->maxErroneousBitsInBorderRate;

fs["minOtsuStdDev"] >> params->minOtsuStdDev;

fs["errorCorrectionRate"] >> params->errorCorrectionRate;

return true;

}

int main(int argc, char *argv[]) {

CommandLineParser parser(argc, argv, keys);

parser.about(about);

int dictionaryId = parser.get("d");

bool showRejected = parser.has("r");

bool estimatePose = parser.has("c");

float markerLength = parser.get("l");

Ptr<:detectorparameters> detectorParams = aruco::DetectorParameters::create();

if(parser.has("dp")) {

bool readOk = readDetectorParameters(parser.get("dp"), detectorParams);

if(!readOk) {

cerr << "Invalid detector parameters file" << endl;

return 0;

}

}

int camId = parser.get("ci");

String video;

if(parser.has("v")) {

video = parser.get("v");

}

if(!parser.check()) {

parser.printErrors();

return 0;

}

Ptr<:dictionary> dictionary =

aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));

Mat camMatrix, distCoeffs;

if(estimatePose) {

bool readOk = readCameraParameters(parser.get("c"), camMatrix, distCoeffs);

if(!readOk) {

cerr << "Invalid camera file" << endl;

return 0;

}

}

VideoCapture inputVideo;

/* int waitTime; if(!video.empty()) { inputVideo.open(video); waitTime = 0; } else { inputVideo.open(camId); waitTime = 10; } inputVideo.set(CAP_PROP_FRAME_WIDTH, 640); inputVideo.set(CAP_PROP_FRAME_HEIGHT , 480); */

double totalTime = 0;

int totalIterations = 0;

g2o::SparseOptimizer optimizer;//全局优化器

//以下三句话要加

g2o::ParameterSE3Offset* cameraOffset = new g2o::ParameterSE3Offset;

cameraOffset->setId(0);

optimizer.addParameter(cameraOffset);

optimizer.setVerbose(true);//调试信息输出

g2o::BlockSolverX::LinearSolverType * linearSolver;//6代表pose的自由度 3代表landmark的自由度

linearSolver= new g2o::LinearSolverDense<:blocksolverx::posematrixtype>();

g2o::BlockSolverX * solver_ptr

= new g2o::BlockSolverX(linearSolver);

//优化方法LM

g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr);

optimizer.setAlgorithm(solver);

Mat inputImage=imread("./squre_80_120/0.jpg");

int num_image=1;

while(true) {

Mat image, imageCopy;

//inputVideo.retrieve(image);

image = inputImage;

double tick = (double)getTickCount();

vector< int > ids;

vector< vector< Point2f > > corners, rejected;

vector< Vec3d > rvecs, tvecs;

// detect markers and estimate pose

aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);

if(estimatePose && ids.size() > 0)

aruco::estimatePoseSingleMarkers(corners, markerLength, camMatrix, distCoeffs, rvecs,

tvecs);

double currentTime = ((double)getTickCount() - tick) / getTickFrequency();

totalTime += currentTime;

// draw results

image.copyTo(imageCopy);

if(ids.size() > 0)

{

aruco::drawDetectedMarkers(imageCopy, corners, ids);

if(estimatePose) {

for(unsigned int i = 0; i < ids.size(); i++)

aruco::drawAxis(imageCopy, camMatrix, distCoeffs, rvecs[i], tvecs[i],

markerLength * 0.5f);

}

}

if(showRejected && rejected.size() > 0)

aruco::drawDetectedMarkers(imageCopy, rejected, noArray(), Scalar(100, 0, 255));

imshow("out", imageCopy);

int key = waitKey(0);

cout << key << endl;

if(key == 1048689) break;//'q'

if(key == 1048675)//'c'

buildMap(ids, corners, rvecs, tvecs, optimizer);

string string_temp = "./squre2/" + to_string(num_image++) +".jpg";

if(num_image == 14)

break;

inputImage=imread(string_temp);

}

//之后开始g2o优化建图等。

optimizer.save("before.g2o");

optimizer.initializeOptimization();

optimizer.optimize(10);

optimizer.save("after.g2o");

return 0;

}

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

aruco板_基于arucoTag的简单slam 的相关文章

  • vscode_c++_slambook 编译配置

    工作目录 配置文件 launch json version 0 2 0 configurations name slamBook程序调试 type cppdbg request launch program fileDirname buil
  • 微信小程序SLAM AR零基础入门教程

    鬼灭之刃花街篇 开播在即 今天带大家零基础使用Kivicube制作一个炭治郎的SLAM AR云手办 可以通过微信小程序将AR版的炭治郎放置在家中 提前感受鬼灭的氛围 先上个GIF大家看看动态的展示效果 在这里先科普一下本次教程使用到的AR技
  • SLAM入门

    SLAM定义 SLAM Simultaneous localization and mapping 同时定位 我在哪里 与建图 我周围有什么 当某种移动设备 汽车 扫地机 手机 无人机 机器人 从一个未知环境的未知地点出发 在运动过程中 通
  • ubuntu系统下配置vscode编译cmake

    文章目录 一 配置vs code运行c 代码 三个关键文件介绍 1 tasks json run helloworld cpp 1 1 打开cpp文件 使其成为活动文件 1 2 按编辑器右上角的播放按钮 1 3生成task文件 1 4 此时
  • 《视觉SLAM十四讲》第一版源码slambook编译调试

    slambook master ch2 编译正常 log如下 slambook master ch2 mkdir build cd build cmake make j8 The C compiler identification is G
  • Ubuntu18.04 安装速腾聚创最新驱动RSLidar_SDK采集XYZIRT格式的激光点云数据 --SLAM不学无术小问题

    Ubuntu18 04 安装速腾聚创最新驱动RSLidar SDK采集XYZIRT格式的激光点云数据 新款驱动支持RS16 RS32 RSBP RS128 RS80 RSM1 B3 RSHELIOS等型号 注意 该教程旨在引导安装 可能现在
  • 基于深度相机的三维重建技术

    本文转载自http www bugevr com zblog id 14 原创作者bugeadmin 转载至我的博客 主要是为了备份 日后查找方便 谢谢原创作者的分享 三维重建 3D Reconstruction 技术一直是计算机图形学和计
  • 各向异性(anisotropic)浅提

    文章目录 各向异性 anisotropic 定义 哪种物体具有各向异性反射 什么导致各向异性反射 总结 各向异性 anisotropic 定义 它指一种存在方向依赖性 这意味着在不同的方向不同的特性 相对于该属性各向同性 当沿不同轴测量时
  • 从零开始一起学习SLAM(9)不推公式,如何真正理解对极约束?

    文章目录 对极几何基本概念 如何得到极线方程 作业 此文发于公众号 计算机视觉life 原文链接 从零开始一起学习SLAM 不推公式 如何真正理解对极约束 自从小白向师兄学习了李群李代数和相机成像模型的基本原理后 感觉书上的内容没那么难了
  • 单目视觉里程记代码

    在Github上发现了一个简单的单目vo 有接近500星 链接如下 https github com avisingh599 mono vo 这个单目里程计主要依靠opencv实现 提取fast角点并进行光流跟踪 然后求取本质矩阵并恢复两帧
  • lego-LOAM跑自己的数据包无法显示全局点云地图解决(速腾聚创RS-LiDAR-16 雷达 )---SLAM不学无术小问题

    LeGo LOAM跑自己的数据包无法显示全局地图问题 注意 本文笔者使用环境 Ubuntu18 04 ROS melodic 版本 背景 3D SLAM新手 在看到了各种狂拽炫酷的3D点云图的之后决定亲自上手一试 首先当然的是最为经典的LO
  • docker dbus-x11

    本来想用terminator启动nvidia docker 显示出图形界面的 结果发现启动的时候出问题了 terminator 1 dbind WARNING 07 31 53 725 Couldn t connect to accessi
  • 快看!那个学vSLAM的上吊了! —— (一)综述

    不同于之前发布的文章 我将使用一种全新的方式 iPad Notability Blog的方式打开这个板块的大门 原因有两个 1 Notability更方便手写长公式 也方便手绘坐标系变换等等 2 之前Apple Pencil找不到了新破费买
  • Ceres Solver从零开始手把手教学使用

    目录 一 简介 二 安装 三 介绍 四 Hello Word 五 导数 1 数值导数 2解析求导 六 实践 Powell函数 一 简介 笔者已经半年没有更新新的内容了 最近学习视觉SLAM的过程中发现自己之前学习的库基础不够扎实 Ceres
  • 舒尔补-边际概率-条件概率

    margin求边际概率的时候喜欢通过舒尔补的形式去操作信息矩阵 如p b c 求积分p a b c da 从上图可知 边缘概率直接看协方差矩阵比较方便 边际概率的方差就是取对应联合分布中相应的协方差块 信息矩阵是由舒尔补的形式计算 此形式也
  • 【Pytorch论文相关代码】使用SOLD2预训练好的模型检测与匹配线段(自己的数据集)

    文章目录 前言 使用流程 检测与匹配结果 前言 论文链接 SOLD2 Self supervised Occlusion aware Line Description and Detection 论文源码 https github com
  • LOAM算法详解

    激光SLAM 帧间匹配方法 Point to Plane ICP NDT Feature based Method 回环检测方法 Scan to Scan Scan to Map LOAM创新点 定位和建图的分离 里程计模块 高频低质量的帧
  • ArUco 位姿估计中的不稳定值

    我正在尝试使用 Aruco 标记找到相机的方向 从旋转矩阵中提取的欧拉角在超过某一点时不稳定 随着相机与标记的距离增加 相机的偏航角值不稳定 标记上的 Z 轴翻转 欧拉角不稳定 每帧都不相同 需要时间才能稳定 如何获得相机和标记之间的偏航角
  • Todesk突然高速通道使用已结束

    今天使用Todesk直接报出如下错误 好像对于海外用户需要付费购买海外会员 大家有没有什么可以替换的远程控制软件的吗 能分享一下吗
  • 详细了解 openCV aruco 标记检测/姿态估计:亚像素精度

    我目前正在研究openCV的 aruco 模块 特别关注ArUco标记和AprilTags的poseEstimation 在研究子像素精度时 我遇到了一种奇怪的行为 如下代码所示 如果我确实提供了 完美 校准 例如 cx cy 等于图像中心

随机推荐