-
Notifications
You must be signed in to change notification settings - Fork 1.8k
/
Copy path_r430.urdf.xacro
130 lines (114 loc) · 5.32 KB
/
_r430.urdf.xacro
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
<?xml version="1.0"?>
<!--
# Copyright 2023 Intel Corporation. All Rights Reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-->
<!--
This is the URDF model for the Intel RealSense 430 camera, in it's
aluminum peripherial evaluation case.
-->
<robot name="sensor_r430" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Includes -->
<xacro:include filename="$(find realsense2_description)/urdf/_materials.urdf.xacro" />
<xacro:macro name="sensor_r430" params="parent *origin name:=camera use_nominal_extrinsics:=false">
<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="r430_cam_depth_to_infra1_offset" value="-0.025"/>
<xacro:property name="r430_cam_depth_to_infra2_offset" value="0.025"/>
<xacro:property name="r430_cam_depth_to_fisheye_offset" value="0.042"/>
<!-- The following values model the aluminum peripherial case for the
R430 camera, with the camera joint represented by the actual
peripherial camera tripod mount -->
<xacro:property name="r430_cam_width" value="0.105"/>
<xacro:property name="r430_cam_height" value="0.039"/>
<xacro:property name="r430_cam_depth" value="0.019"/>
<xacro:property name="r430_cam_mount_from_center_offset" value=".0275"/>
<!-- The following offset is relative the the physical R430 camera peripherial
camera tripod mount -->
<xacro:property name="r430_cam_depth_px" value="0.00"/>
<xacro:property name="r430_cam_depth_py" value="-0.035"/>
<xacro:property name="r430_cam_depth_pz" value="0.028"/>
<!-- camera body, with origin at bottom screw mount -->
<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_link" />
</joint>
<link name="${name}_link">
<visual>
<origin xyz="0 ${-r430_cam_mount_from_center_offset} ${r430_cam_height/2}" rpy="${M_PI/2} 0 ${M_PI/2}"/>
<geometry>
<box size="${r430_cam_width} ${r430_cam_height} ${r430_cam_depth}"/>
<!--<mesh filename="file://$(find realsense2_description)/meshes/r430/r430.dae" />-->
</geometry>
<material name="aluminum"/>
</visual>
<collision>
<origin xyz="0.0 0.0 ${r430_cam_height/2}" rpy="0 0 0"/>
<geometry>
<box size="${r430_cam_depth} ${r430_cam_width} ${r430_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>
<!-- 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}">
<!-- camera depth joints and links -->
<joint name="${name}_depth_joint" type="fixed">
<origin xyz="${r430_cam_depth_px} ${r430_cam_depth_py} ${r430_cam_depth_pz}" rpy="0 0 0"/>
<parent link="${name}_link"/>
<child link="${name}_depth_frame" />
</joint>
<link name="${name}_depth_frame"/>
<joint name="${name}_depth_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="${name}_depth_frame" />
<child link="${name}_depth_optical_frame" />
</joint>
<link name="${name}_depth_optical_frame"/>
<!-- camera left IR joints and links -->
<joint name="${name}_infra1_joint" type="fixed">
<origin xyz="0 ${r430_cam_depth_to_infra1_offset} 0" rpy="0 0 0" />
<parent link="${name}_depth_frame" />
<child link="${name}_infra1_frame" />
</joint>
<link name="${name}_infra1_frame"/>
<joint name="${name}_infra1_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="${name}_infra1_frame" />
<child link="${name}_infra1_optical_frame" />
</joint>
<link name="${name}_infra1_optical_frame"/>
<!-- camera right IR joints and links -->
<joint name="${name}_infra2_joint" type="fixed">
<origin xyz="0 ${r430_cam_depth_to_infra2_offset} 0" rpy="0 0 0" />
<parent link="${name}_depth_frame" />
<child link="${name}_infra2_frame" />
</joint>
<link name="${name}_infra2_frame"/>
<joint name="${name}_infra2_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="${name}_infra2_frame" />
<child link="${name}_infra2_optical_frame" />
</joint>
<link name="${name}_infra2_optical_frame"/>
</xacro:if>
</xacro:macro>
</robot>