forked from xtdrone/XTDrone
85 lines
3.3 KiB
XML
85 lines
3.3 KiB
XML
<?xml version="1.0"?>
|
|
<!--
|
|
|
|
Author: Jonathan Sprinkle, Sam Taylor, Alex Warren
|
|
Copyright (c) 2015 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 the control interfaces for ROS-based control
|
|
through Gazebo. For more information and for the tutorials used to create
|
|
this file, see
|
|
http://gazebosim.org/tutorials/?tut=ros_control#Prerequisites
|
|
|
|
Sensors are included separately, based on the arguments passed to the xacro include
|
|
|
|
-->
|
|
<robot>
|
|
|
|
<gazebo reference="velodyne_link">
|
|
<mu1>0.6</mu1>
|
|
<mu2>0.5</mu2>
|
|
</gazebo>
|
|
|
|
<gazebo reference="velodyne_link">
|
|
<sensor type="ray" name="lidar_sensor">
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<visualize>false</visualize>
|
|
<update_rate>5</update_rate>
|
|
<ray>
|
|
<scan>
|
|
<horizontal>
|
|
<samples>100</samples>
|
|
<resolution>1</resolution>
|
|
<min_angle>${velodyne_min_angle}</min_angle>
|
|
<max_angle>${velodyne_max_angle}</max_angle>
|
|
</horizontal>
|
|
<vertical>
|
|
<samples>20</samples>
|
|
<resolution>1</resolution>
|
|
<min_angle>-0.034906585</min_angle>
|
|
<!-- <max_angle>0.432841654</max_angle> -->
|
|
<max_angle>0.326</max_angle>
|
|
</vertical>
|
|
</scan>
|
|
<range>
|
|
<min>1</min>
|
|
<max>50.0</max>
|
|
<resolution>0.02</resolution>
|
|
</range>
|
|
</ray>
|
|
<!-- <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
|
|
<topicName>/cat/laser/scan</topicName>
|
|
<frameName>laser_link</frameName> -->
|
|
<plugin name="laser_controller" filename="libgazebo_ros_block_laser.so">
|
|
<frameName>velodyne_link</frameName>
|
|
<hokuyoMinIntensity>101</hokuyoMinIntensity>
|
|
<robotNamespace>/$(arg roboname)</robotNamespace>
|
|
<topicName>lidar_points</topicName>
|
|
<gaussianNoise>0.02</gaussianNoise>
|
|
<updateRate>5</updateRate>
|
|
</plugin>
|
|
</sensor>
|
|
</gazebo>
|
|
|
|
</robot>
|
|
|