d435.urdf.xacro 5.41 KB
Newer Older
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
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
<?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 430 camera, in it's
aluminum peripherial evaluation case.
-->

<robot name="sensor_d435" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="sensor_d435" params="parent *origin">
    <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="d435_cam_depth_to_left_ir_offset" value="0.0"/>
    <xacro:property name="d435_cam_depth_to_right_ir_offset" value="-0.050"/>
    <xacro:property name="d435_cam_depth_to_color_offset" value="0.015"/>
  
    <!-- The following values model the aluminum peripherial case for the
  	D435 camera, with the camera joint represented by the actual 
  	peripherial camera tripod mount -->
    <xacro:property name="d435_cam_width" value="0.090"/>
    <xacro:property name="d435_cam_height" value="0.025"/>
    <xacro:property name="d435_cam_depth" value="0.02505"/>
    <xacro:property name="d435_cam_mount_from_center_offset" value="0.0149"/>
  
    <!-- The following offset is relative the the physical D435 camera peripherial
  	camera tripod mount -->
    <xacro:property name="d435_cam_depth_px" value="${d435_cam_mount_from_center_offset}"/>
    <xacro:property name="d435_cam_depth_py" value="0.0175"/>
    <xacro:property name="d435_cam_depth_pz" value="${d435_cam_height/2}"/>

    <material name="aluminum">
	  <color rgba="0.5 0.5 0.5 1"/>
    </material>


    <!-- camera body, with origin at bottom screw mount -->
    <joint name="camera_joint" type="fixed">
      <xacro:insert_block name="origin" />
      <parent link="${parent}"/>
      <child link="camera_bottom_screw_frame" />
    </joint>
    <link name="camera_bottom_screw_frame"/>

    <joint name="camera_link_joint" type="fixed">
      <origin xyz="0 ${d435_cam_depth_py} ${d435_cam_depth_pz}" rpy="0 0 0"/>
      <parent link="camera_bottom_screw_frame"/>
      <child link="camera_link" />
    </joint>

    <link name="camera_link">
      <visual>
      <origin xyz="${d435_cam_mount_from_center_offset} ${-d435_cam_depth_py} 0" rpy="${M_PI/2} 0 ${M_PI/2}"/>
        <geometry>
          <!-- <box size="${d435_cam_width} ${d435_cam_height} ${d435_cam_depth}"/> -->
	  <mesh filename="package://realsense2_camera/meshes/d435.dae" />
          <!--<mesh filename="package://realsense2_camera/meshes/d435/d435.dae" />-->

        </geometry>
        <material name="aluminum"/>
      </visual>
      <collision>
        <origin xyz="0 ${-d435_cam_depth_py} 0" rpy="0 0 0"/>
        <geometry>
        <box size="${d435_cam_depth} ${d435_cam_width} ${d435_cam_height}"/>
        </geometry>
      </collision>
      <inertial>
        <!-- The following are not reliable values, and should not be used for modeling -->
        <mass value="0.564" />
        <origin xyz="0 0 0" />
        <inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257" />
      </inertial>
    </link>
   
    <!-- camera depth joints and links -->
    <joint name="camera_depth_joint" type="fixed">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <parent link="camera_link"/>
      <child link="camera_depth_frame" />
    </joint>
    <link name="camera_depth_frame"/>

    <joint name="camera_depth_optical_joint" type="fixed">
      <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
      <parent link="camera_depth_frame" />
      <child link="camera_depth_optical_frame" />
    </joint>
    <link name="camera_depth_optical_frame"/>
      
    <!-- camera left IR joints and links -->
    <joint name="camera_left_ir_joint" type="fixed">
      <origin xyz="0 ${d435_cam_depth_to_left_ir_offset} 0" rpy="0 0 0" />
      <parent link="camera_depth_frame" />
      <child link="camera_left_ir_frame" />
    </joint>
    <link name="camera_left_ir_frame"/>

    <joint name="camera_left_ir_optical_joint" type="fixed">
      <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
      <parent link="camera_left_ir_frame" />
      <child link="camera_left_ir_optical_frame" />
    </joint>
    <link name="camera_left_ir_optical_frame"/>

    <!-- camera right IR joints and links -->
    <joint name="camera_right_ir_joint" type="fixed">
      <origin xyz="0 ${d435_cam_depth_to_right_ir_offset} 0" rpy="0 0 0" />
      <parent link="camera_depth_frame" />
      <child link="camera_right_ir_frame" />
    </joint>
    <link name="camera_right_ir_frame"/>

    <joint name="camera_right_ir_optical_joint" type="fixed">
      <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
      <parent link="camera_right_ir_frame" />
      <child link="camera_right_ir_optical_frame" />
    </joint>
    <link name="camera_right_ir_optical_frame"/>

    <!-- camera color joints and links -->
    <joint name="camera_color_joint" type="fixed">
      <origin xyz="0 ${d435_cam_depth_to_color_offset} 0" rpy="0 0 0" />
      <parent link="camera_depth_frame" />
      <child link="camera_color_frame" />
    </joint>
    <link name="camera_color_frame"/>

    <joint name="camera_color_optical_joint" type="fixed">
      <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
      <parent link="camera_color_frame" />
      <child link="camera_color_optical_frame" />
    </joint>
    <link name="camera_color_optical_frame"/>
  </xacro:macro>
</robot>