3 <!-- Posix SITL environment launch script -->
4 <arg name="use_urdf" default="false" />
6 <arg name="x" default="0"/>
7 <arg name="y" default="0"/>
8 <arg name="z" default="0"/>
9 <arg name="R" default="0"/>
10 <arg name="P" default="0"/>
11 <arg name="Y" default="0"/>
12 <arg name="est" default="ekf2"/>
14 <arg name="vehicle" default="iris"/>
15 <arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
17 <!-- Generate model from xacro and run robot state publisher -->
18 <arg if="$(arg use_urdf)" name="model" default="$(find px4_simulation_stack)/Tools/sitl_gazebo/models/$(arg vehicle)/urdf/$(arg vehicle).urdf"/>
19 <group if="$(arg use_urdf)">
20 <arg name="mavlink_udp_port" default="14560"/>
21 <arg name="cmd" default="$(find xacro)/xacro $(arg model) mavlink_udp_port:=$(arg mavlink_udp_port) --inorder"/>
22 <param command="$(arg cmd)" name="robot_description" />
24 <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
25 <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
27 <!-- load sdf if not use xacro -->
28 <arg unless="$(arg use_urdf)" name="model" default="$(find px4_simulation_stack)/Tools/sitl_gazebo/models/$(arg vehicle)/$(arg vehicle).sdf"/>
30 <env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
31 <env name="PX4_ESTIMATOR" value="$(arg est)" />
33 <arg name="debug" default="false"/>
34 <arg name="verbose" default="false"/>
35 <arg name="paused" default="false"/>
36 <arg name="respawn_gazebo" default="false"/>
39 <arg name="interactive" default="true"/>
40 <!-- PX4 SITL and Gazebo -->
41 <arg unless="$(arg interactive)" name="px4_command_arg1" value="-d"/>
42 <arg if="$(arg interactive)" name="px4_command_arg1" value=""/>
43 <node name="sitl" pkg="px4" type="px4" output="screen"
44 args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS $(arg px4_command_arg1)" required="true"/>
46 <!-- Launching gzserver -->
47 <include file="$(find px4_simulation_stack)/launch/gazebo/gzserver.launch">
48 <arg name="world_name" value="$(arg world)" />
49 <arg name="debug" value="$(arg debug)" />
50 <arg name="verbose" value="$(arg verbose)" />
51 <arg name="paused" value="$(arg paused)" />
52 <arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
56 <arg name="fcu_url" default="udp://:14540@localhost:14557"/>
57 <arg name="gcs_url" default="" />
58 <arg name="tgt_system" default="1" />
59 <arg name="tgt_component" default="1" />
60 <arg name="log_output" default="screen" />
61 <arg name="fcu_protocol" default="v2.0" />
62 <arg name="respawn_mavros" default="false" />
63 <include file="$(find mavros)/launch/node.launch">
64 <!-- GCS link is provided by SITL -->
65 <arg name="pluginlists_yaml" value="$(find mavros)/launch/px4_pluginlists.yaml" />
66 <arg name="config_yaml" default="$(find px4_simulation_stack)/launch/config/px4_config.yaml"/>
68 <arg name="fcu_url" value="$(arg fcu_url)" />
69 <arg name="gcs_url" value="$(arg gcs_url)" />
70 <arg name="tgt_system" value="$(arg tgt_system)" />
71 <arg name="tgt_component" value="$(arg tgt_component)" />
72 <arg name="log_output" value="$(arg log_output)" />
73 <arg name="fcu_protocol" value="$(arg fcu_protocol)" />
74 <arg name="respawn_mavros" default="$(arg respawn_mavros)" />
78 <!-- spawn urdf generated from xacro -->
79 <node if="$(arg use_urdf)" name="$(anon vehicle_spawn)" pkg="gazebo_ros" type="spawn_model" output="screen" args="-param robot_description -urdf -model $(arg vehicle) -package_to_model -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>
81 <node unless="$(arg use_urdf)" name="$(anon vehicle_spawn)" pkg="gazebo_ros" type="spawn_model" output="screen" args="-sdf -file $(arg model) -model $(arg vehicle) -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>
85 <!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : -->