-
Notifications
You must be signed in to change notification settings - Fork 16
/
Copy pathmodel.sdf
54 lines (52 loc) · 1.79 KB
/
model.sdf
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
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="servo_camera">
<static>1</static>
<link name="link_servo">
<sensor type="camera" name="servo_camera">
<update_rate>30</update_rate>
<camera name="head">
<horizontal_fov>1.5</horizontal_fov>
<image>
<width>1920</width>
<height>1080</height>
</image>
<clip>
<near>0.35</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</camera>
<plugin name="servo_camera_controller" filename="libMRSGazeboCameraPlugin.so">
<alwaysOn>true</alwaysOn>
<updateRate>30</updateRate>
<cameraName>servo_camera</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>/servo_camera_frame</frameName>
<hackBaseline>0.0</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
<x>0.0</x>
<y>0.0</y>
<z>0.0</z>
<roll>0.0</roll>
<pitch>0.0</pitch>
<yaw>0.0</yaw>
<parentFrameName>fcu_uav</parentFrameName>
<sensorBaseFrameName>servo_camera_sensor_frame</sensorBaseFrameName>
</plugin>
</sensor>
</link>
</model>
</sdf>