2021-01-20 17:32:37 +05:30

64 lines
2.6 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.5">
<model name="kinect">
<pose>0 0 0.036 0 0 0</pose>
<link name="link">
<inertial>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.073000 0.276000 0.072000</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://kinect/meshes/kinect.dae</uri>
</mesh>
</geometry>
</visual>
<sensor name="camera" type="depth">
<update_rate>15</update_rate>
<camera>
<horizontal_fov>1.2215</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>12</far>
</clip>
</camera>
<plugin name="camera_plugin" filename="libgazebo_ros_openni_kinect.so">
<robotNamespace>qt_pi</robotNamespace>
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>15</updateRate>
<cameraName>camera_ir</cameraName>
<imageTopicName>/qt_pi/camera_ir/color/image_raw</imageTopicName>
<cameraInfoTopicName>/qt_pi/camera_ir/color/camera_info</cameraInfoTopicName>
<depthImageTopicName>/qt_pi/camera_ir/depth/image_raw</depthImageTopicName>
<depthImageInfoTopicName>/camera_ir/depth/camera_info</depthImageInfoTopicName>
<pointCloudTopicName>/qt_pi/camera_ir/depth/points</pointCloudTopicName>
<frameName>camera_link</frameName>
<pointCloudCutoff>0.05</pointCloudCutoff>
<distortionK1>0</distortionK1>
<distortionK2>0</distortionK2>
<distortionK3>0</distortionK3>
<distortionT1>0</distortionT1>
<distortionT2>0</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</link>
</model>
</sdf>