-
Notifications
You must be signed in to change notification settings - Fork 46
/
asus_camera.urdf.xacro
116 lines (101 loc) · 3.98 KB
/
asus_camera.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926535897931" />
<!--
The asus_camera_model macro only adds the model, it does not also add
the openni gazebo plugin. See the 'asus_camera' macro below for that
-->
<xacro:macro name="asus_camera_model" params="name parent *origin">
<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_link"/>
</joint>
<link name="${name}_link">
<inertial>
<mass value="0.200" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://hector_sensors_description/meshes/asus_camera/asus_camera_simple.dae"/>
</geometry>
</visual>
<!--
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.035 0.185 0.025"/>
</geometry>
</collision>
-->
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://hector_sensors_description/meshes/asus_camera/asus_camera_simple.dae"/>
</geometry>
</collision>
</link>
<joint name="${name}_depth_joint" type="fixed">
<origin xyz="0.0 0.049 0.0" 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.0 ${-M_PI/2}" />
<parent link="${name}_depth_frame" />
<child link="${name}_depth_optical_frame"/>
</joint>
<link name="${name}_depth_optical_frame"/>
<joint name="${name}_rgb_joint" type="fixed">
<origin xyz="0.0 0.022 0.0" rpy="0 0 0" />
<parent link="${name}_link" />
<child link="${name}_rgb_frame"/>
</joint>
<link name="${name}_rgb_frame"/>
<joint name="${name}_rgb_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0.0 ${-M_PI/2}" />
<parent link="${name}_rgb_frame" />
<child link="${name}_rgb_optical_frame"/>
</joint>
<link name="${name}_rgb_optical_frame"/>
</xacro:macro>
<!--
The asus_camera macro only adds the model, and also adds
the openni gazebo plugin.
-->
<xacro:macro name="asus_camera" params="name parent *origin">
<xacro:asus_camera_model name="${name}" parent="${parent}">
<xacro:insert_block name="origin" />
</xacro:asus_camera_model>
<!-- ASUS Xtion PRO camera for simulation -->
<gazebo reference="${name}_depth_frame">
<sensor type="depth" name="${name}">
<update_rate>20</update_rate>
<camera>
<horizontal_fov>${62.8 * M_PI/180.0}</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.5</near>
<far>9</far>
</clip>
</camera>
<plugin name="${name}_camera_controller" filename="libgazebo_ros_openni_kinect.so">
<imageTopicName>${name}/rgb/image_raw</imageTopicName>
<cameraInfoTopicName>${name}/rgb/camera_info</cameraInfoTopicName>
<depthImageTopicName>${name}/depth/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>${name}/depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>${name}/depth/points</pointCloudTopicName>
<frameName>${name}_depth_optical_frame</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>