-
Notifications
You must be signed in to change notification settings - Fork 2
/
stereo_camera.urdf.xacro
65 lines (62 loc) · 2.17 KB
/
stereo_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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="stereo_camera"
params="reference ns frame_id update_rate baseline hfov width height format near far">
<gazebo reference="${reference}">
<sensor type="multicamera" name="stereo_camera">
<update_rate>${update_rate}</update_rate>
<camera name="left">
<pose>0 0 0 0 -1.5707 1.5707</pose>
<horizontal_fov>${hfov}</horizontal_fov>
<image>
<width>${width}</width>
<height>${height}</height>
<format>${format}</format>
</image>
<clip>
<near>${near}</near>
<far>${far}</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<camera name="right">
<pose>${baseline} 0 0 0 -1.5707 1.5707</pose>
<horizontal_fov>${hfov}</horizontal_fov>
<image>
<width>${width}</width>
<height>${height}</height>
<format>${format}</format>
</image>
<clip>
<near>${near}</near>
<far>${far}</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so">
<alwaysOn>true</alwaysOn>
<cameraName>${ns}/camera</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>${frame_id}</frameName>
<hackBaseline>${baseline}</hackBaseline>
<!--<rightFrameName>right_camera_optical_frame</rightFrameName>-->
<!-- NOTE: Distortion is currently unused -->
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>