80 lines
2.5 KiB
XML
80 lines
2.5 KiB
XML
<?xml version='1.0'?>
|
|
<sdf version='1.0'>
|
|
<model name='monocular_camera'>
|
|
<pose>0.0 0.0 0 0 0 0</pose>
|
|
<link name='link'>
|
|
<inertial>
|
|
<mass>0.001</mass>
|
|
<inertia>
|
|
<ixx>4.15e-6</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>2.407e-6</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>2.407e-6</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<visual name='visual'>
|
|
<geometry>
|
|
<box>
|
|
<size>0.01 0.01 0.01</size>
|
|
</box>
|
|
</geometry>
|
|
</visual>
|
|
<sensor name='camera' type='camera'>
|
|
<camera name='__default__'>
|
|
<horizontal_fov>2.0944</horizontal_fov>
|
|
<image>
|
|
<width>1280</width>
|
|
<height>720</height>
|
|
</image>
|
|
<clip>
|
|
<near>0.1</near>
|
|
<far>100</far>
|
|
</clip>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0.0</mean>
|
|
<stddev>0.001</stddev>
|
|
</noise>
|
|
<lens>
|
|
<type>custom</type>
|
|
<custom_function>
|
|
<c1>1.05</c1>
|
|
<c2>4</c2>
|
|
<f>1</f>
|
|
<fun>tan</fun>
|
|
</custom_function>
|
|
<scale_to_hfov>1</scale_to_hfov>
|
|
<cutoff_angle>3.1415</cutoff_angle>
|
|
</lens>
|
|
</camera>
|
|
<always_on>1</always_on>
|
|
<update_rate>30</update_rate>
|
|
<visualize>0</visualize>
|
|
<plugin name='camera_plugin' filename='libgazebo_ros_camera.so'>
|
|
<robotNamespace></robotNamespace>
|
|
<alwaysOn>true</alwaysOn>
|
|
<imageTopicName>image_raw</imageTopicName>
|
|
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
|
|
<updateRate>30.0</updateRate>
|
|
<cameraName>camera</cameraName>
|
|
<frameName>/camera_link</frameName>
|
|
<CxPrime>640</CxPrime>
|
|
<Cx>640</Cx>
|
|
<Cy>360</Cy>
|
|
<hackBaseline>0</hackBaseline>
|
|
<focalLength>369.502083</focalLength>
|
|
<distortionK1>0.0</distortionK1>
|
|
<distortionK2>0.0</distortionK2>
|
|
<distortionK3>0.0</distortionK3>
|
|
<distortionT1>0.0</distortionT1>
|
|
<distortionT2>0.0</distortionT2>
|
|
</plugin>
|
|
</sensor>
|
|
<self_collide>0</self_collide>
|
|
<kinematic>0</kinematic>
|
|
</link>
|
|
</model>
|
|
</sdf>
|