This repository has been archived by the owner on Feb 6, 2023. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 356
/
camera_snippets.xacro
251 lines (228 loc) · 8.95 KB
/
camera_snippets.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
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
<?xml version="1.0"?>
<!-- Copyright (c) 2016 The UUV Simulator Authors.
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.
-->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Macro for a minimal collision block (for when you do not want collision block but gazebo needs one) -->
<xacro:macro name="no_collision">
<collision>
<geometry>
<cylinder length="${0.000001}" radius="${0.000001}" />
</geometry>
<origin xyz="0 0 0" rpy="0 ${0.5*pi} 0"/>
</collision>
</xacro:macro>
<xacro:macro name="default_camera" params="namespace parent_link suffix *origin">
<xacro:regular_camera_plugin_macro
namespace="${namespace}"
suffix="${suffix}"
parent_link="${parent_link}"
topic="camera"
mass="0.1"
update_rate="30"
hfov="1.5125"
width="768"
height="492"
stddev="0.02"
scale="1.0">
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
<xacro:insert_block name="origin" />
</xacro:regular_camera_plugin_macro>
</xacro:macro>
<xacro:macro name="wideangle_camera" params="namespace parent_link suffix *origin">
<xacro:regular_camera_plugin_macro
namespace="${namespace}"
suffix="${suffix}"
parent_link="${parent_link}"
topic="camera"
mass="0.015"
update_rate="30"
hfov="1.8125"
width="768"
height="492"
stddev="0.02"
scale="1.0">
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
<xacro:insert_block name="origin" />>
</xacro:regular_camera_plugin_macro>
</xacro:macro>
<xacro:macro name="regular_camera_plugin_macro"
params="namespace suffix parent_link topic mass update_rate
hfov width height stddev scale
*inertia *origin">
<!-- Sensor link -->
<link name="${namespace}/camera${suffix}_link">
<inertial>
<xacro:insert_block name="inertia" />
<mass value="${mass}" />
<origin xyz="0 0 0" rpy="0 0 0" />
</inertial>
<visual>
<geometry>
<mesh filename="file://$(find uuv_sensor_ros_plugins)/meshes/oe14-372.dae" scale="${scale} ${scale} ${scale}"/>
</geometry>
</visual>
<xacro:no_collision/>
</link>
<joint name="${namespace}/camera${suffix}_joint" type="revolute">
<xacro:insert_block name="origin" />
<parent link="${parent_link}" />
<child link="${namespace}/camera${suffix}_link" />
<limit upper="0" lower="0" effort="0" velocity="0" />
<axis xyz="1 0 0"/>
</joint>
<link name="${namespace}/camera${suffix}_link_optical">
<xacro:box_inertial x="0.0001" y="0.0001" z="0.0001" mass="0.001">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:box_inertial>
<collision>
<!-- todo: gazebo needs a collision volume or it will ignore the pose of
the joint that leads to this link (and assume it to be the identity) -->
<geometry>
<cylinder length="0.000001" radius="0.000001"/>
</geometry>
<origin xyz="0 0 0" rpy="0 ${0.5*pi} 0"/>
</collision>
</link>
<joint name="${namespace}/camera${suffix}_optical_joint" type="revolute">
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
<parent link="${namespace}/camera${suffix}_link"/>
<child link="${namespace}/camera${suffix}_link_optical"/>
<limit upper="0" lower="0" effort="0" velocity="0" />
<axis xyz="1 0 0"/>
</joint>
<gazebo reference="${namespace}/camera${suffix}_link">
<sensor type="camera" name="camera${suffix}">
<update_rate>${update_rate}</update_rate>
<camera name="camera${suffix}">
<horizontal_fov>${hfov}</horizontal_fov>
<image>
<width>${width}</width>
<height>${height}</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>3000</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>${stddev}</stddev>
</noise>
</camera>
<plugin name="camera${suffix}_controller" filename="libgazebo_ros_camera.so">
<updateRate>${update_rate}</updateRate>
<cameraName>${namespace}/camera${suffix}</cameraName>
<frameName>camera${suffix}_link_optical</frameName>
<attenuationR>0.0</attenuationR>
<attenuationG>0.0</attenuationG>
<attenuationB>0.0</attenuationB>
<backgroundR>0</backgroundR>
<backgroundG>0</backgroundG>
<backgroundB>0</backgroundB>
<!-- required for ros depth cam -->
<imageTopicName>${topic}_image</imageTopicName>
<pointCloudTopicName>${topic}_cloud</pointCloudTopicName>
<depthImageTopicName>${topic}_depth</depthImageTopicName>
<depthImageCameraInfoTopicName>${topic}_depth_info</depthImageCameraInfoTopicName>
<pointCloudCutoff>10.0</pointCloudCutoff>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
<xacro:macro name="underwater_camera_plugin_macro"
params="namespace suffix parent_link topic mass update_rate
hfov width height stddev
*inertia *origin">
<!-- Sensor link -->
<link name="${namespace}/camera${suffix}_link">
<inertial>
<xacro:insert_block name="inertia" />
<mass value="${mass}" />
<origin xyz="0 0 0" rpy="0 0 0" />
</inertial>
<visual>
<geometry>
<mesh filename="file://$(find uuv_sensor_ros_plugins)/meshes/oe14-372.dae" scale="1 1 1"/>
</geometry>
</visual>
<xacro:no_collision/>
</link>
<joint name="${namespace}/camera${suffix}_joint" type="revolute">
<xacro:insert_block name="origin" />
<parent link="${parent_link}" />
<child link="${namespace}/camera${suffix}_link" />
<axis xyz="1 0 0"/>
<limit upper="0" lower="0" effort="0" velocity="0" />
</joint>
<link name="${namespace}/camera${suffix}_link_optical">
<xacro:box_inertial x="0.0001" y="0.0001" z="0.0001" mass="0.001">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:box_inertial>
<collision>
<!-- todo: gazebo needs a collision volume or it will ignore the pose of
the joint that leads to this link (and assume it to be the identity) -->
<geometry>
<cylinder length="0.000001" radius="0.000001"/>
</geometry>
<origin xyz="0 0 0" rpy="0 ${0.5*pi} 0"/>
</collision>
</link>
<joint name="${namespace}/camera${suffix}_optical_joint" type="revolute">
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
<parent link="${namespace}/camera${suffix}_link"/>
<child link="${namespace}/camera${suffix}_link_optical"/>
<limit upper="0" lower="0" effort="0" velocity="0" />
<axis xyz="1 0 0"/>
</joint>
<gazebo reference="${namespace}/camera${suffix}_link">
<sensor type="depth" name="camera${suffix}">
<update_rate>${update_rate}</update_rate>
<camera name="camera${suffix}">
<horizontal_fov>${hfov}</horizontal_fov>
<image>
<width>${width}</width>
<height>${height}</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.1</near>
<far>3000</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>${stddev}</stddev>
</noise>
</camera>
<plugin name="camera${suffix}_controller" filename="libuuv_gazebo_ros_camera_plugin.so">
<updateRate>${update_rate}</updateRate>
<cameraName>${namespace}/camera${suffix}</cameraName>
<frameName>${namespace}/camera${suffix}_link</frameName>
<attenuationR>0.01</attenuationR>
<attenuationG>0.01</attenuationG>
<attenuationB>0.003</attenuationB>
<backgroundR>0</backgroundR>
<backgroundG>0</backgroundG>
<backgroundB>0</backgroundB>
<!-- required for ros depth cam -->
<imageTopicName>${topic}_image</imageTopicName>
<pointCloudTopicName>${topic}_cloud</pointCloudTopicName>
<depthImageTopicName>${topic}_depth</depthImageTopicName>
<depthImageCameraInfoTopicName>${topic}_depth_info</depthImageCameraInfoTopicName>
<pointCloudCutoff>10.0</pointCloudCutoff>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>