Intel Realsense T265使用教程
0 更新日志
- 2022-3-15 增加 “关闭T265回环检测”
- 2022-3-15 增加 T265轨迹保存
- 2021-10-28 增加T265坐标系描述
1 T265参数
1.1 硬件参数
1、T265采用了Movidius Myriad 2视觉处理单元(VPU),V-SLAM算法都直接在VPU上运行 可直接输出6DOF相机位姿
2、T265使用了双目鱼眼相机 分辨率848X800分辨率 30HZ 单色图像 视场角 163° Fov(±5°)
3、IMU型号为 BMI-055
4、相机与IMU的参数都保存在了传感器中,可通过示例demo直接读取出相机的内参和相机与IMU之间的外参
5、相机外形尺寸 108 x 24.5 x 12.5 mm
1.2 坐标系描述
265放置方式: 将摄像头镜头面对准正前方,即摄像头坐标系Z轴指向正前方、Y轴指向地面、X轴指向右。
T265输出的里程计(话题:/camera/odom/sample)的坐标系与官方提供的图片坐标系有不同。实际测量到的坐标系为,正前方为X_odom轴正方向、左边为Y_odom轴正方向、天向为Z_odom轴正方向。
IMU输出值的坐标系为官方图片中的坐标系。
2 T265 数据读取
2.1 环境安装
安装方法有两种,一种是源码安装,另一种是使用命令安装2进制包进行安装,第二种方法较为简单。
step 1: 注册服务器公钥
sudo apt-key adv --keyserver keys.gnupg.net --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE || sudo apt-key adv --keyserver hkp://keyserver.ubuntu.com:80 --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE
step 2: 添加镜像源
Ubuntu 1604 使用如下命令
sudo add-apt-repository "deb http://realsense-hw-public.s3.amazonaws.com/Debian/apt-repo xenial main" -u
Ubuntu 1804 使用如下命令
sudo add-apt-repository "deb https://librealsense.intel.com/Debian/apt-repo $(lsb_release -cs) main" -u
如果上述如果上述命令不能使用,再替换为
sudo add-apt-repository "deb http://realsense-hw-public.s3.amazonaws.com/Debian/apt-repo bionic main" -u
step 3: 安装环境
sudo apt-get update
sudo apt-get install librealsense2-dkms librealsense2-utils librealsense2-dev librealsense2-dbg
step 4: 插上T265 在终端里面运行 realsense-viewer 测试
realsense-viewer
成功运行以后可以得到如下的界面效果
下面是一个晃动T265的视频,一旦运动速度过快的话,输出的位姿就会飞掉。
2.2 读取T265内外参数信息
T265在出厂前就对相机进行了标定,每个相机内部都带有相机的内参和外参。在终端中输入以下命令,即可读取到T265的配置信息
rs-enumerate-devices
如果需要读取到相机内参和外参[4] ,以及IMU的参数则可以使用如下命令(添加-c参数)
rs-enumerate-devices -c
2.3 使用ROS包读取T265数据
使用环境ROS Kinetic 版本
step1 安装依赖项:
sudo apt-get install ros-kinetic-ddynamic-reconfigure
step2 下载安装ROS包 realsense-ros
cd ~/catkin_ws/src/
git clone https://github.com/IntelRealSense/realsense-ros.git
cd realsense-ros/
git checkout `git tag | sort -V | grep -P "^2.\d+\.\d+" | tail -1`
cd ..
catkin_make -DCATKIN_ENABLE_TESTING=False -DCMAKE_BUILD_TYPE=Release
step3 启动测试demo,即可看到T265的位姿数据
roslaunch realsense2_camera demo_t265.launch
如果需要查看图像数据,则需要对rs_t265.launch lanunch文件中使能图像输出
step4 重新启动测试demo即可查看到图像数据
roslaunch realsense2_camera demo_t265.launch
图像数据发布的Topic 图像数据30Hz
- /camera/fisheye1/camera_info
- /camera/fisheye1/image_raw
- /camera/fisheye2/camera_info
- /camera/fisheye2/image_raw
IMU 数据发布的Topic, 陀螺仪数据200Hz 加速度数据为 63Hz
- /camera/accel/sample
- /camera/gyro/sample
里程计发布的Topic 200Hz
- /camera/odom/sample
如果需要将加速度和陀螺仪的数据整合到一个topic发布的话,则需设置如下参数:
此时IMU的发布频率为200Hz
2.4 使用Opencv库读取T265图像
数据
主函数内容:
#include
#include
#include
#include
#include
#include
using namespace std;
using namespace cv;
int main(int argc,char** argv)
{
rs2::config cfg;
// 使能 左右目图像数据
cfg.enable_stream(RS2_STREAM_FISHEYE,1, RS2_FORMAT_Y8);
cfg.enable_stream(RS2_STREAM_FISHEYE,2, RS2_FORMAT_Y8);
// 使能 传感器的POSE和6DOF IMU数据
cfg.enable_stream(RS2_STREAM_POSE, RS2_FORMAT_6DOF);
rs2::pipeline pipe;
pipe.start(cfg);
rs2::frameset data;
while (1)
{
data = pipe.wait_for_frames();
// Get a frame from the pose stream
auto f = data.first_or_default(RS2_STREAM_POSE);
auto pose = f.as<rs2::pose_frame>().get_pose_data();
cout<<"px: "<<pose.translation.x<<" py: "<<pose.translation.y<<" pz: "<<pose.translation.z<<
"vx: "<<pose.velocity.x<<" vy: "<<pose.velocity.y<<" vz: "<<pose.velocity.z<<endl;
cout<<"ax: "<<pose.acceleration.x<<" ay: "<<pose.acceleration.y<<" az: "<<pose.acceleration.z<<
"gx: "<<pose.angular_velocity.x<<" gy: "<<pose.angular_velocity.y<<" gz: "<<pose.angular_velocity.z<<endl;
rs2::frame image_left = data.get_fisheye_frame(1);
rs2::frame image_right = data.get_fisheye_frame(2);
if (!image_left || !image_right)
break;
cv::Mat cv_image_left(cv::Size(848, 800), CV_8U, (void*)image_left.get_data(), cv::Mat::AUTO_STEP);
cv::Mat cv_image_right(cv::Size(848, 800), CV_8U, (void*)image_right.get_data(), cv::Mat::AUTO_STEP);
cv::imshow("left", cv_image_left);
cv::imshow("right", cv_image_right);
cv::waitKey(1);
}
return 0;
}
即可读取到T265的图像数据和位姿数据
3 T265附加功能开发
3.1 保存T265的轨迹到txt文件
在测试算法的过程中需要对比T265算法输出轨迹,因此涉及到将T265发布的里程计数据保存在txt文本中。 程序思路是接收 T265发布的 “/camera/odom/sample” 话题,然后将Topic上的里程计数据按照 EVO评估脚本的顺序写入到txt文件保存。这个功能代码包可以从这个github地址[7]下载。
3.2 关闭T265回环检测功能
在使用T265作为视觉里程计时,当T265运动一圈以后回到起点或到过此前走过的场景时,轨迹可能会出现跳变的情况,这种跳变对控制和导航都存在较大的影响。
T265可以通过在launch文件中加入一个参数对回环检测的功能进行关闭(github上答案[6])
<rosparam>
/camera/tracking_module/enable_relocalization: false
</rosparam>
这里使用的代码参考了博客[2]和[3]中的内容。 T265在VINS_Fusion上运行的方法可参考博客[5]。
参考资料
[1] https://www.intelrealsense.com/get-started-tracking-camera/
[2] https://blog.csdn.net/u011341856/article/details/106430940?utm_medium=distribute.pc_relevant.none-task-blog-BlogCommendFromMachineLearnPai2-1.add_param_isCf&depth_1-utm_source=distribute.pc_relevant.none-task-blog-BlogCommendFromMachineLearnPai2-1.add_param_isCf
[3] https://github.com/IntelRealSense/librealsense/tree/master/examples/pose
[4] https://github.com/IntelRealSense/librealsense/tree/master/tools/enumerate-devices
[5] https://blog.csdn.net/weixin_44631150/article/details/104495156?utm_medium=distribute.wap_aggpage_search_result.none-task-blog-2allsobaiduend~default-2-104495156.nonecase&utm_term=t265%E8%BE%93%E5%87%BAimu
[6] https://github.com/IntelRealSense/realsense-ros/issues/779
[7] 保存T265轨迹 https://github.com/RuPingCen/transform_t265
欢迎大家点赞在评论区交流讨论(cenruping@vip.qq.com) O(∩_∩)O
或者加群交流(1149897304)
评论记录:
回复评论: