Added camera depth controller for gazebo. Removed uneeded stl file.
This commit is contained in:
parent
cd5c50599c
commit
10ce33c06c
Binary file not shown.
@ -25,4 +25,48 @@
|
|||||||
<link name="helmet-xtion">
|
<link name="helmet-xtion">
|
||||||
<xacro:visuals_collisions_helmet_xtion/>
|
<xacro:visuals_collisions_helmet_xtion/>
|
||||||
</link>
|
</link>
|
||||||
|
<joint name="helmet-to-xtion" type="fixed">
|
||||||
|
<parent link="helmet-xtion"/>
|
||||||
|
<child link="xtion"/>
|
||||||
|
<origin xyz="0 0 0.0075" rpy="-${PI_2} 0 -${PI_2}"/>
|
||||||
|
</joint>
|
||||||
|
<link name="xtion"/>
|
||||||
|
|
||||||
|
<!-- GAZEBO SPECIFIC FOR XTION -->
|
||||||
|
<gazebo reference="helmet-xtion">
|
||||||
|
<sensor type="depth" name="xtion">
|
||||||
|
<always_on>true</always_on>
|
||||||
|
<update_rate>30.0</update_rate>
|
||||||
|
<camera>
|
||||||
|
<horizontal_fov>${60.0*PI/180.0}</horizontal_fov>
|
||||||
|
<image>
|
||||||
|
<format>R8G8B8</format>
|
||||||
|
<width>640</width>
|
||||||
|
<height>480</height>
|
||||||
|
</image>
|
||||||
|
<clip>
|
||||||
|
<near>0.05</near>
|
||||||
|
<far>8.0</far>
|
||||||
|
</clip>
|
||||||
|
</camera>
|
||||||
|
<plugin name="xtion_camera_controller" filename="libgazebo_ros_openni_kinect.so">
|
||||||
|
<cameraName>xtion</cameraName>
|
||||||
|
<alwaysOn>true</alwaysOn>
|
||||||
|
<updateRate>30</updateRate>
|
||||||
|
<imageTopicName>xtion/rgb/image_raw</imageTopicName>
|
||||||
|
<depthImageTopicName>xtion/depth/image_raw</depthImageTopicName>
|
||||||
|
<pointCloudTopicName>xtion/depth/points</pointCloudTopicName>
|
||||||
|
<cameraInfoTopicName>xtion/rgb/camera_info</cameraInfoTopicName>
|
||||||
|
<depthImageCameraInfoTopicName>xtion/depth/camera_info</depthImageCameraInfoTopicName>
|
||||||
|
<frameName>xtion</frameName>
|
||||||
|
<baseline>0.1</baseline>
|
||||||
|
<distortion_k1>0.0</distortion_k1>
|
||||||
|
<distortion_k2>0.0</distortion_k2>
|
||||||
|
<distortion_k3>0.0</distortion_k3>
|
||||||
|
<distortion_t1>0.0</distortion_t1>
|
||||||
|
<distortion_t2>0.0</distortion_t2>
|
||||||
|
<pointCloudCutoff>0.4</pointCloudCutoff>
|
||||||
|
</plugin>
|
||||||
|
</sensor>
|
||||||
|
</gazebo>
|
||||||
</robot>
|
</robot>
|
Loading…
x
Reference in New Issue
Block a user