硬件参数
- T265采用了Movidius Myriad 2视觉处理单元(VPU),V-SLAM算法都直接在VPU上运行 可直接输出6DOF相机位姿
- 使用双目鱼眼相机 分辨率848X800分辨率 30HZ 单色图像 视场角 163° Fov(±5°)
- IMU型号为 BMI-055
SDK
从 Intel® RealSense™ SDK 2.0 (v2.54.1)
中已经明确说明版本不再支持T265 最后一个支持的版本为 v2.50.0 ,而期间的几个版本虽然支持T265但官方说明不在对其进行测试。
安装方式
其中一种方式,测试可用
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15
| mkdir ~/releases-2.50.0 cd ~/releases-2.50.0
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`
mkdir build cd build cmake .. make make install
|
SDK启动
Realsense2
此库为双目提供驱动,包括 T265 D400系列等
安装
1
| sudo apt-get install ros-$ROS_DISTRO-realsense2-camera
|
一般情况下,安装后库会存在于 /opt/ros/noetic/share/realsense2_camera
(与ros安装路径有关)
也可以通过源码安装,放置在自己工作空间下
部分常用launch
启动T265
1
| roslaunch realsense2_camera rs_t265.launch
|
同时启动T265和D400系列
1
| roslaunch realsense2_camera rs_d400_and_t265.launch
|
通过话题获取数据
话题
以使用 roslaunch realsense2_camera rs_t265.launch
开启T265为例,使用 rostopic
查看话题,能够得到以下话题
1 2 3 4 5 6 7 8 9 10 11 12 13 14
| /camera/accel/imu_info /camera/accel/metadata /camera/accel/sample /camera/gyro/imu_info /camera/gyro/metadata /camera/gyro/sample /camera/odom/metadata /camera/odom/sample /camera/realsense2_camera_manager/bond /camera/tracking_module/parameter_descriptions /camera/tracking_module/parameter_updates /diagnostics /tf /tf_static
|
常用的有
里程计发布
/camera/odom/sample
IMU发布
陀螺仪 /camera/accel/sample
200Hz
加速度 /camera/gyro/sample
63Hz
里程计信息demo
可以通过订阅 /camera/odom/sample
话题,输出里程坐标
其输出坐标系信息为:正前方为X轴正方向、左边为Y轴正方向、天向为Z轴正方向 即FLU
输出频率为 200Hz
CPP
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36
| #include <ros/ros.h> #include <nav_msgs/Odometry.h>
void poseCallback(const nav_msgs::Odometry::ConstPtr& msg) { geometry_msgs::Point position = msg->pose.pose.position; geometry_msgs::Quaternion orientation = msg->pose.pose.orientation;
ROS_INFO("位置 X: %f", position.x); ROS_INFO("位置 Y: %f", position.y); ROS_INFO("位置 Z: %f", position.z); ROS_INFO("姿态 W: %f", orientation.w); ROS_INFO("姿态 X: %f", orientation.x); ROS_INFO("姿态 Y: %f", orientation.y); ROS_INFO("姿态 Z: %f", orientation.z); ROS_INFO("----------------------------------"); }
int main(int argc, char** argv) { setlocale(LC_ALL,""); ros::init(argc, argv, "t265_motion_subscriber");
ros::NodeHandle nh;
ros::Subscriber sub = nh.subscribe("/camera/odom/sample", 10, poseCallback);
ros::spin();
return 0; }
|
Python
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32
| import rospy from nav_msgs.msg import Odometry import time
def pose_callback(msg: Odometry): position = msg.pose.pose.position orientation = msg.pose.pose.orientation
rospy.loginfo("位置 X: %f", position.x) rospy.loginfo("位置 Y: %f", position.y) rospy.loginfo("位置 Z: %f", position.z) rospy.loginfo("姿态 W: %f", orientation.w) rospy.loginfo("姿态 X: %f", orientation.x) rospy.loginfo("姿态 Y: %f", orientation.y) rospy.loginfo("姿态 Z: %f", orientation.z) rospy.loginfo("----------------------------------")
time.sleep(1)
def main(): rospy.init_node("t265_motion_subscriber")
rospy.Subscriber("/camera/odom/sample", Odometry, pose_callback)
rospy.spin()
if __name__ == '__main__': main()
|
注意事项
- T265等需要在计算机开机后插入,否则将无法被识别