ORB-SLAM2学习笔记6之D435i双目IR相机运行ROS版ORB-SLAM2并发布位姿pose的rostopic

文章目录

  • 0 引言
  • 1 D435i相机配置
  • 2 新增发布双目位姿功能
    • 2.1 新增d435i_stereo.cc代码
    • 2.2 修改CMakeLists.txt
    • 2.3 新增配置文件D435i.yaml
  • 3 编译运行和结果
    • 3.1 编译运行
    • 3.2 结果
    • 3.3 可能出现的问题

0 引言

ORB-SLAM2学习笔记1已成功编译安装ROS版本ORB-SLAM2到本地,以及ORB-SLAM2学习笔记5成功用EuRoc、TUM、KITTI开源数据来运行ROSORB-SLAM2,并生成轨迹。但实际ROS视觉SLAM工程落地时,一般搭配传感器实时发出位姿poserostopic,本篇就以D435i相机的双目IR相机作为输入,运行ROSORB-SLAM2,最后发出poserostopic

👉 ORB-SLAM2 github: https://github.com/raulmur/ORB_SLAM2

本文系统环境:

  • Ubuntu18.04
  • ROS-melodic
  • ROS版ORB-SLAM2
  • D435i相机和驱动

1 D435i相机配置

默认已在Ubuntu18.04系统上安装ROS版的D435i相机驱动,比如本文驱动安装目录~/catkin_rs/src/realsense-ros

安装后,默认是不开双目IR相机,需要自行修改配置:

# 激活环境
source /catkin_rs/devel/setup.bash
# roscd 进入到配置文件目录下
roscd realsense2_camera/launch/
# 打开 rs_camera.launch 配置文件进行修改
vim rs_camera.launch

打开后,主要是如下的字段需要修改成 true,这样就能打开双目IR相机,分辨率也可自行修改。

  <arg name="infra_width"         default="848"/><arg name="infra_height"        default="480"/><arg name="enable_infra"        default="true"/><arg name="enable_infra1"       default="true"/><arg name="enable_infra2"       default="true"/>
...

2 新增发布双目位姿功能

2.1 新增d435i_stereo.cc代码

ORB_SLAM2/Examples/ROS/ORB_SLAM2/src/目录下新增d435i_stereo.cc 代码文件,如下代码片段来增加:

#include<iostream>
#include<algorithm>
#include<fstream>
#include<chrono>#include<tf/transform_broadcaster.h>
#include "../../../include/Converter.h"
#include <nav_msgs/Path.h>#include <ros/ros.h>
#include <cv_bridge/cv_bridge.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>#include<opencv2/core/core.hpp>#include"../../../include/System.h"using namespace std;class ImageGrabber
{
public:ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){}void GrabStereo(const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight);ORB_SLAM2::System* mpSLAM;bool do_rectify;cv::Mat M1l,M2l,M1r,M2r;
};ros::Publisher pose_pub;
nav_msgs::Path stereo_path;
ros::Publisher stereo_path_pub;int main(int argc, char **argv)
{ros::init(argc, argv, "RGBD");ros::start();if(argc != 4){cerr << endl << "Usage: rosrun ORB_SLAM2 Stereo path_to_vocabulary path_to_settings do_rectify" << endl;ros::shutdown();return 1;}    // Create SLAM system. It initializes all system threads and gets ready to process frames.ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::STEREO,true);ImageGrabber igb(&SLAM);stringstream ss(argv[3]);ss >> boolalpha >> igb.do_rectify;if(igb.do_rectify){      // Load settings related to stereo calibrationcv::FileStorage fsSettings(argv[2], cv::FileStorage::READ);if(!fsSettings.isOpened()){cerr << "ERROR: Wrong path to settings" << endl;return -1;}cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r;fsSettings["LEFT.K"] >> K_l;fsSettings["RIGHT.K"] >> K_r;fsSettings["LEFT.P"] >> P_l;fsSettings["RIGHT.P"] >> P_r;fsSettings["LEFT.R"] >> R_l;fsSettings["RIGHT.R"] >> R_r;fsSettings["LEFT.D"] >> D_l;fsSettings["RIGHT.D"] >> D_r;int rows_l = fsSettings["LEFT.height"];int cols_l = fsSettings["LEFT.width"];int rows_r = fsSettings["RIGHT.height"];int cols_r = fsSettings["RIGHT.width"];if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() ||rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0){cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl;return -1;}cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,igb.M1l,igb.M2l);cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,igb.M1r,igb.M2r);}ros::NodeHandle nh;//message_filters::Subscriber<sensor_msgs::Image> left_sub(nh, "/camera/left/image_raw", 1);//message_filters::Subscriber<sensor_msgs::Image> right_sub(nh, "camera/right/image_raw", 1);message_filters::Subscriber<sensor_msgs::Image> left_sub(nh, "/camera/infra1/image_rect_raw", 1);message_filters::Subscriber<sensor_msgs::Image> right_sub(nh, "/camera/infra2/image_rect_raw", 1);typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> sync_pol;message_filters::Synchronizer<sync_pol> sync(sync_pol(10), left_sub,right_sub);sync.registerCallback(boost::bind(&ImageGrabber::GrabStereo,&igb,_1,_2));pose_pub = nh.advertise<geometry_msgs::PoseStamped>("ORB_SLAM/pose", 5);stereo_path_pub = nh.advertise<nav_msgs::Path>("ORB_SLAM/path",10);ros::spin();// Stop all threadsSLAM.Shutdown();// Save camera trajectorySLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory_TUM_Format.txt");SLAM.SaveTrajectoryTUM("FrameTrajectory_TUM_Format.txt");SLAM.SaveTrajectoryKITTI("FrameTrajectory_KITTI_Format.txt");ros::shutdown();return 0;
}void ImageGrabber::GrabStereo(const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight)
{// Copy the ros image message to cv::Mat.cv_bridge::CvImageConstPtr cv_ptrLeft;try{cv_ptrLeft = cv_bridge::toCvShare(msgLeft);}catch (cv_bridge::Exception& e){ROS_ERROR("cv_bridge exception: %s", e.what());return;}cv_bridge::CvImageConstPtr cv_ptrRight;try{cv_ptrRight = cv_bridge::toCvShare(msgRight);}catch (cv_bridge::Exception& e){ROS_ERROR("cv_bridge exception: %s", e.what());return;}if(do_rectify){cv::Mat imLeft, imRight;cv::remap(cv_ptrLeft->image,imLeft,M1l,M2l,cv::INTER_LINEAR);cv::remap(cv_ptrRight->image,imRight,M1r,M2r,cv::INTER_LINEAR);mpSLAM->TrackStereo(imLeft,imRight,cv_ptrLeft->header.stamp.toSec()).clone();}else{cv::Mat Tcw;Tcw = mpSLAM->TrackStereo(cv_ptrLeft->image,cv_ptrRight->image,cv_ptrLeft->header.stamp.toSec());geometry_msgs::PoseStamped pose;pose.header.stamp = ros::Time::now();pose.header.frame_id ="path";cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t(); // Rotation informationcv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3); // translation informationvector<float> q = ORB_SLAM2::Converter::toQuaternion(Rwc);tf::Transform new_transform;new_transform.setOrigin(tf::Vector3(twc.at<float>(0, 0), twc.at<float>(0, 1), twc.at<float>(0, 2)));tf::Quaternion quaternion(q[0], q[1], q[2], q[3]);new_transform.setRotation(quaternion);tf::poseTFToMsg(new_transform, pose.pose);pose_pub.publish(pose);stereo_path.header.frame_id="path";stereo_path.header.stamp=ros::Time::now();stereo_path.poses.push_back(pose);stereo_path_pub.publish(stereo_path);}
}

上述代码已经写入了D435i相机双目IR相机发出的topic,分别是左目/camera/infra1/image_rect_raw,右目/camera/infra2/image_rect_raw;发布的位姿posetopicORB_SLAM/pose,如果用的不是D435i,比如zed双目相机,可以自行修改。

2.2 修改CMakeLists.txt

由于新增了发布功能的代码文件,那对应的CMakeLists.txt也需要新增对应的编译和链接的设置,如下所示,在ORB_SLAM2/Examples/ROS/ORB_SLAM2/CMakeLists.txt 文件的结尾新增:

# Node for d435i_stereo camera
# 设置了编译的代码文件`d435i_stereo.cc`和可执行文件的名字
rosbuild_add_executable(D435i_Stereo
src/d435i_stereo.cc
)target_link_libraries(D435i_Stereo
${LIBS}
)

2.3 新增配置文件D435i.yaml

同时也要新增对应的配置文件D435i.yaml,可新增到ORB_SLAM2/Examples/Stereo/D435i.yaml,文件类似ORB_SLAM2/Examples/Stereo/EuRoC.yaml,如下所示,主要修改第一部分的内参部分(fx,fy,cx,cy)即可,相机的内参获取方法,可通过roslaunch realsense2_camera rs_camera.launch启动相机后,再通过rostopic echo /camera/infra1/camera_info来获取。

%YAML:1.0#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------# Camera calibration and distortion parameters (OpenCV) 
Camera.fx: 427.03680419921875
Camera.fy: 427.03680419921875
Camera.cx: 427.3993835449219
Camera.cy: 236.4639129638672Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0Camera.width: 848
Camera.height: 480# Camera frames per second 
Camera.fps: 15.0# stereo baseline times fx
Camera.bf: 50.0# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1# Close/Far threshold. Baseline times.
ThDepth: 35#--------------------------------------------------------------------------------------------
# Stereo Rectification. Only if you need to pre-rectify the images.
# Camera.fx, .fy, etc must be the same as in LEFT.P
#--------------------------------------------------------------------------------------------
LEFT.height: 480
LEFT.width: 752
LEFT.D: !!opencv-matrixrows: 1cols: 5dt: ddata:[-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0]
LEFT.K: !!opencv-matrixrows: 3cols: 3dt: ddata: [458.654, 0.0, 367.215, 0.0, 457.296, 248.375, 0.0, 0.0, 1.0]
LEFT.R:  !!opencv-matrixrows: 3cols: 3dt: ddata: [0.999966347530033, -0.001422739138722922, 0.008079580483432283, 0.001365741834644127, 0.9999741760894847, 0.007055629199258132, -0.008089410156878961, -0.007044357138835809, 0.9999424675829176]
LEFT.P:  !!opencv-matrixrows: 3cols: 4dt: ddata: [435.2046959714599, 0, 367.4517211914062, 0,  0, 435.2046959714599, 252.2008514404297, 0,  0, 0, 1, 0]RIGHT.height: 480
RIGHT.width: 752
RIGHT.D: !!opencv-matrixrows: 1cols: 5dt: ddata:[-0.28368365, 0.07451284, -0.00010473, -3.555907e-05, 0.0]
RIGHT.K: !!opencv-matrixrows: 3cols: 3dt: ddata: [457.587, 0.0, 379.999, 0.0, 456.134, 255.238, 0.0, 0.0, 1]
RIGHT.R:  !!opencv-matrixrows: 3cols: 3dt: ddata: [0.9999633526194376, -0.003625811871560086, 0.007755443660172947, 0.003680398547259526, 0.9999684752771629, -0.007035845251224894, -0.007729688520722713, 0.007064130529506649, 0.999945173484644]
RIGHT.P:  !!opencv-matrixrows: 3cols: 4dt: ddata: [435.2046959714599, 0, 367.4517211914062, -47.90639384423901, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1200# ORB Extractor: Scale factor between levels in the scale pyramid 	
ORBextractor.scaleFactor: 1.2# ORB Extractor: Number of levels in the scale pyramid	
ORBextractor.nLevels: 8# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast			
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500

3 编译运行和结果

3.1 编译运行

全部修改后,可回到ORB_SLAM2工程目录下,重新执行命令进行编译:

# chmod 之前执行过可忽略
chmod +x build_ros.sh
./build_ros.sh

编译完成后,首先连接D435i相机到电脑上(USB3.0),然后执行命令启动D435i相机:

source /catkin_rs/devel/setup.bash
roslaunch realsense2_camera rs_camera.launch

然后再新开终端,执行D435i_Stereo

# ORB_SLAM2工程目录下
rosrun ORB_SLAM2 D435i_Stereo Vocabulary/ORBvoc.txt Examples/Stereo/D435i.yaml false

3.2 结果

执行上述命令后,在加载完词袋后,会自动打开两个可视化界面:

ORB-SLAM2: Current Frame
请添加图片描述

ORB-SLAM2: Map Viewer
请添加图片描述

可以用rostopic list可查看到已经发出的位姿topic :

/ORB_SLAM/path
/ORB_SLAM/pose

也可以用rostopic echo /ORB_SLAM/pose查看具体的位姿信息:

header: seq: 3287stamp: secs: 0nsecs:         0frame_id: "path"
pose: position: x: 0.0335485860705y: -0.0102641582489z: -0.0411500893533orientation: x: -0.042415473676y: -0.00852415898276z: -0.015283392766w: 0.998946787478

至此,成功用D435i相机的双目IR相机作为输入,运行ROSORB-SLAM2,最后发出poserostopic

3.3 可能出现的问题

问题1:

如果如下所示的问题,启动后很快自动关闭,可能是特征点太少的原因,调整相机的朝向,保证相机视野范围内多一点特征:

terminate called after throwing an instance of 'cv::Exception'what():  /build/opencv-L2vuMj/opencv-3.2.0+dfsg/modules/core/src/matrix.cpp:483: error: (-215) 0 <= _rowRange.start && _rowRange.start <= _rowRange.end && _rowRange.end <= m.rows in function MatAborted (core dumped)

Reference:

  • https://github.com/raulmur/ORB_SLAM2



须知少时凌云志,曾许人间第一流。



⭐️👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍🌔

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.rhkb.cn/news/82451.html

如若内容造成侵权/违法违规/事实不符,请联系长河编程网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

搭建Repo服务器

1 安装repo 参考&#xff1a;清华大学开源软件镜像站:Git Repo 镜像使用帮助 2 创建manifest仓库 2.1 创建仓库 git init --bare manifest.git2.2 创建default.xml文件 default.xml文件内容&#xff1a; <?xml version"1.0" encoding"UTF-8" ?…

4.2、Flink任务怎样读取文件中的数据

目录 1、前言 2、readTextFile&#xff08;已过时&#xff0c;不推荐使用&#xff09; 3、readFile&#xff08;已过时&#xff0c;不推荐使用&#xff09; 4、fromSource(FileSource) 推荐使用 1、前言 思考: 读取文件时可以设置哪些规则呢&#xff1f; 1. 文件的格式(tx…

【C++】数据结构与算法:常用排序算法

&#x1f60f;★,:.☆(&#xffe3;▽&#xffe3;)/$:.★ &#x1f60f; 这篇文章主要介绍常用排序算法。 学其所用&#xff0c;用其所学。——梁启超 欢迎来到我的博客&#xff0c;一起学习&#xff0c;共同进步。 喜欢的朋友可以关注一下&#xff0c;下次更新不迷路&#x1…

单片机、嵌入式的大神都平时浏览什么网站?

我平时也喜欢收藏些有关嵌入式的学习网站&#xff0c;压箱底的记录翻出来总结下 1、综合网站 哔哩哔哩 (゜-゜)つロ 干杯~-bilibili//B站是一个有很多好资料的网站 https://github.com/nhivp/Awesome-Embedded //github开源项目网站&#xff0c;这个是我找到嵌入式综合相关的…

PS的一些智能对象是怎么用的?用于包装设计该怎么使用?

大家都对一些效果图不太理解&#xff0c;我现在就献丑给大家讲一下&#xff0c;教程都是网友盛传的&#xff0c;我自己学习并且有所体会。 一般做的非常好的PS效果图都是外国人自己做的&#xff0c;所以大多数效果图都是英文&#xff0c;细心的网友会发现&#xff0c;中文的是一…

chatGPT能力培训,客户最关注的99个方向

前言&#xff1a; chatGPT的主要应用&#xff0c;包括文本生成、图像生成和图文关联三大核心方向&#xff1a; 用户的在实际的工作和学习过程中&#xff0c;最关心的内容&#xff0c;可以按照上述类别进行划分&#xff0c;我们总结了&#xff0c;相关的插头GPT能力培训的相关主…

基于OFDM通信系统的低复杂度的资源分配算法matlab性能仿真

目录 1.算法运行效果图预览 2.算法运行软件版本 3.部分核心程序 4.算法理论概述 5.算法完整程序工程 1.算法运行效果图预览 2.算法运行软件版本 matlab2022a 3.部分核心程序 .......................................................................%子载波分配[~,po…

MySQL:表的约束和基本查询

表的约束 表的约束——为了让插入的数据符合预期。 表的约束很多&#xff0c;这里主要介绍如下几个&#xff1a; null/not null,default, comment, zerofill&#xff0c;primary key&#xff0c;auto_increment&#xff0c;unique key 。 空属性 两个值&#xff1a;null&am…

C 语言的 ctype.h 头文件

C 语言的 ctype.h 头文件包含了很多字符函数的函数原型, 可以专门用来处理一个字符, 这些函数都以一个字符作为实参. ctype.h 中的字符测试函数如表所示: 这些测试函数返回 0 或 1, 即 false 或 true. ctype.h 中的字符映射函数如表所示: 字符测试函数不会修改原始实参, 只会…

list交并补差集合

list交并补差集合 工具类依赖 <dependency><groupId>org.apache.commons</groupId><artifactId>commons-lang3</artifactId><version>3.8.1</version> </dependency><dependency><groupId>commons-collections&…

内生安全构建数据存储

一、数据安全成为防护核心&#xff0c;存储安全防护不容有失 1、数据作为企业的核心资产亟需重点保护&#xff0c;数据安全已成网络空间防护核心 2、国家高度重视关键信息基础设施的数据安全&#xff0c;存储安全已成为审核重点 二、存储安全是数据安全的关键一环&#xff0c;应…

解决github打不开的方法

解决github打不开的方法 本文参考文章&#xff1a;解决可ping通但无法访问github网站的问题 一、确定域名github.com的ip地址 进入网址 IP/服务器github.com的信息 - 站长工具 (chinaz.com)&#xff0c;查看 ip 地址。 20.205.243.166 github.com二、确定域名github.global.…

【论文研读】MARLlib 的架构分析

【论文研读】MARLlib: A Scalable Multi-agent Reinforcement Learning Library 和尚念经 多智能体强化学习框架研究。 多智能体强化学习库。 多智能体强化学习算法实现。 多智能体强化学习环境的统一化&#xff0c;标准化。 多智能体强化学习算法解析。 多智能体强化学习 算法…

5W2H分析法模版

&#xff08;1&#xff09;WHAT——是什么&#xff0c;目的是什么&#xff0c;做什么工作。 条件是什么&#xff0c;哪一部分工作要做&#xff0c;目的是什么&#xff0c;重点是什么&#xff0c;与什么有关系&#xff0c;功能是什么&#xff0c;规范是什么&#xff0c;工作对象…

【IDEA+Spark Streaming 3.4.1+Dstream监控套接字流统计WordCount保存至MySQL8】

【IDEASpark Streaming 3.4.1Dstream监控套接字流统计WordCount保存至MySQL8】 把DStream写入到MySQL数据库中 Spark 3.4.1MySQL 8.0.30sbt 1.9.2 文章目录 【IDEASpark Streaming 3.4.1Dstream监控套接字流统计WordCount保存至MySQL8】前言一、背景说明二、使用步骤1.引入库2…

时序数据库 TDengine 与 WhaleStudio 完成相互兼容性测试认证

近年来&#xff0c;开源及其价值获得社会各界的广泛认可&#xff0c;无论是国家政策导向还是企业数字化转型&#xff0c;都在加速拥抱开源。对于如操作系统、数据库等基础软件来说&#xff0c;开源更是成为驱动技术创新的有力途径。 在此背景下&#xff0c;近日&#xff0c;涛…

Feign

一、为什么使用Feign 二、Feign和RestTemplate的区别 三、自定义配置 四、Feign日志 1.配置文件方式 2.java代码方式

TS 踩坑之路(四)之 Vue3

一、在使用定义默认值withDefaults和defineProps 组合时&#xff0c;默认值设置报错 代码案例 报错信息 不能将类型“{ isBackBtn: false; }”分配给类型“(props: PropsType) > RouteMsgType”。 对象字面量只能指定已知属性&#xff0c;并且“isBackBtn”不在类型“(pro…

【机器学习】在 MLOps构建项目 ( MLOps2)

My MLOps tutorials: Tutorial 1: A Beginner-Friendly Introduction to MLOps教程 2&#xff1a;使用 MLOps 构建机器学习项目 一、说明 如果你希望将机器学习项目提升到一个新的水平&#xff0c;MLOps 是该过程的重要组成部分。在本文中&#xff0c;我们将以经典手写数字分类…

【车道线】TwinLiteNet 复现过程全纪录

码字不易&#xff0c;喜欢的请点赞收藏&#xff01;&#xff01;&#xff01;&#xff01;&#xff01; 论文全文翻译&#xff1a;【freespace】TwinLiteNet: An Efficient and Lightweight Model for Driveable Area and Lane Segmentation_莫克_Cheney的博客-CSDN博客 目录…