XTDrone/sitl_config/usv/vrx_gazebo/launch/vrx.launch

67 lines
2.7 KiB
XML

<?xml version="1.0"?>
<launch>
<env name="ROSCONSOLE_CONFIG_FILE" value="$(find vrx_gazebo)/config/custom_rosconsole.conf"/>
<!-- Gazebo world to load -->
<arg name="world" default="$(find vrx_gazebo)/worlds/example_course.world" />
<!-- If true, run gazebo GUI -->
<arg name="gui" default="true" />
<!-- If true, run gazebo in verbose mode -->
<arg name="verbose" default="false"/>
<!-- Set various other gazebo arguments-->
<arg name="extra_gazebo_args" default=""/>
<!-- Start in a default namespace -->
<arg name="namespace" default="wamv"/>
<!-- Do we lock the vessel to the world? -->
<arg name="wamv_locked" default="false" />
<!-- Start paused? -->
<arg name="paused" default="false"/>
<!-- Initial USV location and attitude-->
<arg name="x" default="158" />
<arg name="y" default="108" />
<arg name="z" default="0.1" />
<arg name="P" default="0" />
<arg name="R" default="0" />
<arg name="Y" default="-2.76" />
<!-- Allow user specified thruster configurations
H = stern trusters on each hull
T = H with a lateral thruster
X = "holonomic" configuration -->
<arg name="thrust_config" default="T" />
<!-- Do we load the VRX sensor suite? -->
<arg name="vrx_sensors_enabled" default="true" />
<!-- Start Gazebo with the world file -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world)"/>
<arg name="verbose" value="$(arg verbose)"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="$(arg gui)" />
<arg name="extra_gazebo_args" value="$(arg extra_gazebo_args)"/>
</include>
<!-- Load robot model -->
<!-- Determine which model -->
<arg name="h_config" value="$(eval int((thrust_config)=='H'))"/>
<arg name="t_config" value="$(eval int((thrust_config)=='T'))"/>
<arg name="x_config" value="$(eval int((thrust_config)=='X'))"/>
<!-- For now - can only use the T configuration! -->
<arg if="$(arg t_config)" name="urdf" default="$(find wamv_gazebo)/urdf/wamv_gazebo.urdf.xacro"/>
<param name="$(arg namespace)/robot_description"
command="$(find xacro)/xacro &#x002D;&#x002D;inorder '$(arg urdf)'
locked:=$(arg wamv_locked)
thruster_config:=$(arg thrust_config)
vrx_sensors_enabled:=$(arg vrx_sensors_enabled)
namespace:=$(arg namespace) "/>
<!-- Spawn model in Gazebo -->
<node name="spawn_model" pkg="gazebo_ros" type="spawn_model"
args="-x $(arg x) -y $(arg y) -z $(arg z)
-R $(arg R) -P $(arg P) -Y $(arg Y)
-urdf -param $(arg namespace)/robot_description -model wamv"/>
</launch>