XTDrone/sitl_config/ugv/catvehicle/launch/robotviz.launch

55 lines
2.3 KiB
XML

<!--
Author: Jonathan Sprinkle
Copyright (c) 2016 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 azcar during playback
or whenever gazebo is not running
How to execute it:
=================
roslaunch catvehicle robotviz.launch
-->
<launch>
<arg name="robot_name" default="catvehicle" />
<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"/>
<!-- get xml file from the urdf folder -->
<!--param name="catvehicle/robot_description" command="cat $(find catvehicle)/urdf/catvehicle_urdf.xml"/-->
<param name="catvehicle/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)'" />
</launch>