px4-firmware/launch/single_vehcile_spawn.launch

34 lines
1.3 KiB
Plaintext
Raw Normal View History

<launch>
<!-- Posix SITL environment launch script -->
<arg name="x" default="0"/>
<arg name="y" default="0"/>
<arg name="z" default="0"/>
<arg name="R" default="0"/>
<arg name="P" default="0"/>
<arg name="Y" default="0"/>
2018-01-01 00:21:44 -04:00
<arg name="est" default="ekf2"/>
<arg name="vehicle" default="iris"/>
<arg name="ID" default="1"/>
<arg name="rcS" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_$(arg ID)"/>
<arg name="mavlink_udp_port" default="14560" />
2018-02-05 16:33:38 -04:00
<arg name="cmd" default="$(find xacro)/xacro $(find px4)/Tools/sitl_gazebo/models/rotors_description/urdf/$(arg vehicle)_base.xacro rotors_description_dir:=$(find px4)/Tools/sitl_gazebo/models/rotors_description mavlink_udp_port:=$(arg mavlink_udp_port) --inorder"/>
2018-02-05 16:33:38 -04:00
<param command="$(arg cmd)" name="rotors_description" />
<node name="sitl_$(arg ID)" pkg="px4" type="px4" output="screen"
args="$(find px4) $(arg rcS)">
</node>
<node name="$(arg vehicle)_$(arg ID)_spawn" output="screen" pkg="gazebo_ros" type="spawn_model"
2018-02-05 16:33:38 -04:00
args="-urdf -param rotors_description -model $(arg vehicle)_$(arg ID) -package_to_model -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>
</launch>
<!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : -->