73 lines
3.2 KiB
XML
73 lines
3.2 KiB
XML
<!--
|
|
|
|
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 launch file loads the worlds and models for the catvehicle
|
|
|
|
-->
|
|
|
|
<launch>
|
|
|
|
<arg name="paused" default="false"/>
|
|
<arg name="use_sim_time" default="true"/>
|
|
<arg name="gui" default="false"/>
|
|
<arg name="headless" default="false"/>
|
|
<arg name="debug" default="false"/>
|
|
<arg name="worldfile" default="enter_worldfile_no_path.world"/>
|
|
|
|
<!-- change these defaults here, or as a cmd line arg, in order to turn off -->
|
|
<!-- sensors that you aren't using, thus freeing up computational resources -->
|
|
<!-- and reducing storage space for your bagfiles -->
|
|
<arg name="front_laser_points" default="true"/>
|
|
<arg name="velodyne_points" default="true"/>
|
|
<arg name="camera_right" default="true"/>
|
|
<arg name="camera_left" default="true"/>
|
|
<!-- change these defaults here, to see further left with the velodyne -->
|
|
<arg name="velodyne_max_angle" default="0.4"/>
|
|
<!-- change these defaults here, to see further right with the velodyne -->
|
|
<arg name="velodyne_min_angle" default="-0.4"/>
|
|
|
|
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
|
<arg name="world_name" value="$(find catvehicle)/worlds/$(arg worldfile)"/>
|
|
<arg name="debug" value="$(arg debug)" />
|
|
<arg name="gui" value="$(arg gui)" />
|
|
<arg name="paused" value="$(arg paused)"/>
|
|
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
|
|
<arg name="headless" value="$(arg headless)"/>
|
|
</include>
|
|
|
|
<group ns="catvehicle">
|
|
<param name="robot_description"
|
|
command="$(find xacro)/xacro.py '$(find catvehicle)/urdf/catvehicle.xacro' roboname:='catvehicle' front_laser_points:='$(arg front_laser_points)' velodyne_points:='$(arg velodyne_points)' camera_right:='$(arg camera_right)' camera_left:='$(arg camera_left)' velodyne_max_angle:='$(arg velodyne_max_angle)' velodyne_min_angle:='$(arg velodyne_min_angle)'" />
|
|
|
|
<include file="$(find catvehicle)/launch/catvehicle.launch">
|
|
<arg name="robot_name" value="catvehicle"/>
|
|
<arg name="init_pose" value="-x 0 -y 0 -z 0"/>
|
|
<arg name="config_file" value="catvehicle_control.yaml"/>
|
|
</include>
|
|
</group>
|
|
|
|
|
|
</launch>
|