XTDrone/sitl_config/ugv/catvehicle/urdf/catvehicle_triclops.gazebo

89 lines
2.9 KiB
XML

<?xml version="1.0"?>
<!--
Author: Jonathan Sprinkle, Sam Taylor, Alex Warren, Rahul Bhadani
Hannah Grace Mason, Joe Macinnes, Landon Chase Bentley
Copyright (c) 2015-2018 Arizona Board of Regents
All rights reserved.
Permission is hereby granted, without written agreement and without
license or royalty fees, to use, copy, modify, and distribute this
software and its documentation for any purpose, provided that the
above copyright notice and the following two paragraphs appear in
all copies of this software.
IN NO EVENT SHALL THE ARIZONA BOARD OF REGENTS BE LIABLE TO ANY PARTY
FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES
ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN
IF THE ARIZONA BOARD OF REGENTS HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGE.
THE ARIZONA BOARD OF REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY
AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER
IS ON AN "AS IS" BASIS, AND THE ARIZONA BOARD OF REGENTS HAS NO OBLIGATION
TO PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
Summary:
This file includes gazebo reference for front stereo camera simulation mounted
on the top of the car. For more information and for the tutorials used to create
this file, see
http://gazebosim.org/tutorials/?tut=ros_control#Prerequisites
-->
<robot>
<!--triclops camera-->
<gazebo reference="triclops_link">
<mu1>0.6</mu1>
<mu2>0.5</mu2>
</gazebo>
<gazebo reference="triclops_link">
<sensor type="camera" name="triclops">
<update_rate>16.0</update_rate>
<camera name="triclops">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>752</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_triclops_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<robotNamespace>/$(arg roboname)</robotNamespace>
<cameraName>triclops</cameraName>
<imageTopicName>triclops/left/image</imageTopicName>
<cameraInfoTopicName>camera_triclops_info</cameraInfoTopicName>
<frameName>triclops_link</frameName>
<hackBaseline>0.12</hackBaseline>
<Fx>376.0</Fx>
<Fy>376.0</Fy>
<Cx>376.0</Cx>
<Cy>240.0</Cy>
<distortionK1>-0.2</distortionK1>
<distortionK2>0.08</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>5e-5</distortionT1>
<distortionT2>-1e-4</distortionT2>
</plugin>
</sensor>
</gazebo>
</robot>