XTDrone/sitl_config/usv/vrx_gazebo/launch/sandisland.launch

79 lines
3.5 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"/>
<!-- If true, start in paused state -->
<arg name="paused" default="false"/>
<!-- Set various other gazebo arguments-->
<arg name="extra_gazebo_args" default=""/>
<!-- Start in a default namespace -->
<arg name="namespace" default="wamv"/>
<!-- 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" />
<!-- If true, show non-competition ROS topics (/gazebo/model_states, /vrx/debug/wind/direction, etc.)-->
<arg name="non_competition_mode" default="true"/>
<arg name="enable_ros_network" value="$(arg non_competition_mode)"/>
<env name="VRX_DEBUG" value="$(arg non_competition_mode)"/>
<env unless="$(arg non_competition_mode)" name="GAZEBO_MODEL_PATH" value="$(find vrx_gazebo)/models:$(find wamv_gazebo)/models:$(find wamv_description)/models:$(optenv GAZEBO_MODEL_PATH)"/>
<!-- 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="H" />
<!-- Do you want to enable sensors? -->
<arg name="camera_enabled" default="false" />
<arg name="gps_enabled" default="false" />
<arg name="imu_enabled" default="false" />
<arg name="lidar_enabled" default="false" />
<arg name="ground_truth_enabled" default="false" />
<!-- 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="enable_ros_network" value="$(arg enable_ros_network)"/>
<arg name="extra_gazebo_args" value="$(arg extra_gazebo_args)"/>
</include>
<!-- Load robot model -->
<arg 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)'
thruster_config:=$(arg thrust_config)
camera_enabled:=$(arg camera_enabled)
gps_enabled:=$(arg gps_enabled)
imu_enabled:=$(arg imu_enabled)
lidar_enabled:=$(arg lidar_enabled)
ground_truth_enabled:=$(arg ground_truth_enabled)
namespace:=$(arg namespace) "/>
<!-- Spawn model in Gazebo, script depending on non_competition_mode -->
<node name="spawn_model" pkg="gazebo_ros" type="spawn_model" if="$(arg non_competition_mode)"
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"/>
<node name="spawn_wamv" pkg="vrx_gazebo" type="spawn_wamv.bash" unless="$(arg non_competition_mode)"
args="-x $(arg x) -y $(arg y) -z $(arg z)
-R $(arg R) -P $(arg P) -Y $(arg Y)
--urdf $(arg urdf) --model wamv"/>
</launch>