Skip to content

Commit

Permalink
add t265 camera
Browse files Browse the repository at this point in the history
  • Loading branch information
eliasdc committed Jan 7, 2025
1 parent 06fa323 commit 28fe085
Show file tree
Hide file tree
Showing 3 changed files with 145 additions and 0 deletions.
Binary file added realsense2_description/meshes/t265.stl
Binary file not shown.
135 changes: 135 additions & 0 deletions realsense2_description/urdf/_t265.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,135 @@
<?xml version="1.0"?>

<!--
License: Apache 2.0. See LICENSE file in root directory.
Copyright(c) 2017 Intel Corporation. All Rights Reserved
This is the URDF model for the Intel RealSense T265 camera, in it's
aluminum peripherial evaluation case.
-->

<robot name="sensor_t265" xmlns:xacro="http://ros.org/wiki/xacro">
<!--Includes-->
<xacro:include filename="$(find realsense2_description)/urdf/_materials.urdf.xacro" />
<xacro:include filename="$(find realsense2_description)/urdf/_t265.gazebo.xacro"/>

<xacro:macro name="sensor_t265" params="parent *origin name:=camera odom_frame:=odom_frame use_nominal_extrinsics:=false">
<xacro:property name="deg_to_rad" value="0.01745329251994329577" />
<xacro:property name="M_PI" value="3.1415926535897931" />

<!-- The following values are approximate, and the camera node
publishing TF values with actual calibrated camera extrinsic values -->
<xacro:property name="fisheye1_offset_x" value="0.0"/>
<xacro:property name="fisheye1_offset_y" value="0.03200"/>
<xacro:property name="fisheye1_offset_z" value="0.0"/>

<xacro:property name="fisheye2_offset_x" value="0.0"/>
<xacro:property name="fisheye2_offset_y" value="-0.03200"/>
<xacro:property name="fisheye2_offset_z" value="0.0"/>

<xacro:property name="imu_offset_x" value="0.00655"/>
<xacro:property name="imu_offset_y" value="0.022"/>
<xacro:property name="imu_offset_z" value="0.0"/>

<xacro:property name="module_center_offset" value="0.00910"/>

<!-- camera body, with origin at camera_link -->
<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_frame" />
</joint>
<link name="${name}_frame">
<visual>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 -${M_PI/2}" />
<geometry>
<mesh filename="package://realsense2_description/meshes/t265.stl" />
</geometry>
<material name="aluminum" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 -${M_PI/2}"/>
<geometry>
<mesh filename="package://realsense2_description/meshes/t265.stl" />
</geometry>
</collision>
<inertial>
<!-- The following are not reliable values, and should not be used for modeling -->
<mass value="0.068024" />
<origin xyz="0 0 0" rpy="${M_PI/2} 0 -${M_PI/2}" />
<inertia ixx="0.0000039782" ixy="0.0" ixz="0.000000034641" iyy="0.000065045" iyz="0.0" izz="0.000067499" />
</inertial>
</link>

<joint name="${name}_frame_joint" type="fixed">
<origin xyz="0 ${module_center_offset} 0" rpy="0 ${M_PI} 0"/>
<parent link="${name}_frame"/>
<child link="${name}_link" />
</joint>
<link name="${name}_link" />

<!-- Use the nominal extrinsics between camera frames if the calibrated extrinsics aren't being published. e.g. running the device in simulation -->
<xacro:if value="${use_nominal_extrinsics}">
<joint name="${name}_fisheye1_rgb_joint" type="fixed">
<origin xyz="${fisheye1_offset_x} ${fisheye1_offset_y} ${fisheye1_offset_z}" rpy="0 -${M_PI} 0"/>
<parent link="${name}_link"/>
<child link="${name}_fisheye1_rgb_frame" />
</joint>
<link name="${name}_fisheye1_rgb_frame"/>

<joint name="${name}_fisheye2_rgb_joint" type="fixed">
<origin xyz="${fisheye2_offset_x} ${fisheye2_offset_y} ${fisheye2_offset_z}" rpy="0 -${M_PI} 0"/>
<parent link="${name}_link"/>
<child link="${name}_fisheye2_rgb_frame" />
</joint>
<link name="${name}_fisheye2_rgb_frame"/>

<joint name="${name}_fisheye1_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${M_PI/2} 0 -${M_PI/2}"/>
<parent link="${name}_fisheye1_rgb_frame"/>
<child link="${name}_fisheye1_optical_frame" />
</joint>
<link name="${name}_fisheye1_optical_frame"/>

<joint name="${name}_fisheye2_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${M_PI/2} 0 -${M_PI/2}"/>
<parent link="${name}_fisheye2_rgb_frame"/>
<child link="${name}_fisheye2_optical_frame" />
</joint>
<link name="${name}_fisheye2_optical_frame"/>


<!-- camera depth joints and links -->
<joint name="${name}_gyro_joint" type="fixed">
<origin xyz="${imu_offset_x} ${imu_offset_y} ${imu_offset_z}" rpy="0 0 ${M_PI}"/>
<parent link="${name}_link"/>
<child link="${name}_gyro_frame" />
</joint>
<link name="${name}_gyro_frame"/>
<joint name="${name}_accel_joint" type="fixed">
<origin xyz="${imu_offset_x} ${imu_offset_y} ${imu_offset_z}" rpy="0 0 ${M_PI}"/>
<parent link="${name}_link"/>
<child link="${name}_accel_frame" />
</joint>
<link name="${name}_accel_frame"/>

<joint name="${name}_gyro_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${M_PI/2} 0 -${M_PI/2}"/>
<parent link="${name}_gyro_frame"/>
<child link="${name}_gyro_optical_frame" />
</joint>
<link name="${name}_gyro_optical_frame"/>
<joint name="${name}_accel_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${M_PI/2} 0 -${M_PI/2}"/>
<parent link="${name}_accel_frame"/>
<child link="${name}_accel_optical_frame" />
</joint>
<link name="${name}_accel_optical_frame"/>
</xacro:if>

<!-- Realsense Gazebo Plugin -->
<xacro:gazebo_t265 camera_name="${name}" fisheye1_reference_link="${name}_fisheye1_rgb_frame" fisheye2_reference_link="${name}_fisheye2_rgb_frame" fisheye1_optical_frame="${name}_fisheye1_optical_frame" fisheye2_optical_frame="${name}_fisheye2_optical_frame"/>

</xacro:macro>

</robot>
10 changes: 10 additions & 0 deletions realsense2_description/urdf/test_t265_camera.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<?xml version="1.0"?>
<robot name="realsense2_camera" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="use_nominal_extrinsics" default="false"/>
<xacro:include filename="$(find realsense2_description)/urdf/_t265.urdf.xacro" />

<link name="base_link" />
<xacro:sensor_t265 parent="base_link" use_nominal_extrinsics="$(arg use_nominal_extrinsics)">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:sensor_t265>
</robot>

0 comments on commit 28fe085

Please sign in to comment.