forked from Archive/PX4-Autopilot
32 lines
1.8 KiB
XML
32 lines
1.8 KiB
XML
<?xml version="1.0"?>
|
|
<launch>
|
|
<!-- Posix SITL environment launch script -->
|
|
<!-- launchs PX4 SITL and spawns vehicle -->
|
|
<!-- vehicle pose -->
|
|
<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"/>
|
|
<!-- vehcile model and config -->
|
|
<arg name="est" default="ekf2"/>
|
|
<arg name="vehicle" default="plane"/>
|
|
<arg name="ID" default="1"/>
|
|
<env name="PX4_SIM_MODEL" value="gazebo-classic_$(arg vehicle)" />
|
|
<arg name="mavlink_udp_port" default="14560"/>
|
|
<arg name="mavlink_tcp_port" default="4560"/>
|
|
<!-- PX4 configs -->
|
|
<arg name="interactive" default="true"/>
|
|
<!-- generate sdf vehicle model -->
|
|
<arg name="cmd" default="xmlstarlet ed -d '//plugin[@name="mavlink_interface"]/mavlink_tcp_port' -s '//plugin[@name="mavlink_interface"]' -t elem -n mavlink_tcp_port -v $(arg mavlink_tcp_port) $(find px4)/Tools/simulation/gazebo-classic/sitl_gazebo-classic/models/$(arg vehicle)/$(arg vehicle).sdf"/>
|
|
<param command="$(arg cmd)" name="model_description"/>
|
|
<!-- PX4 SITL -->
|
|
<arg unless="$(arg interactive)" name="px4_command_arg1" value=""/>
|
|
<arg if="$(arg interactive)" name="px4_command_arg1" value="-d"/>
|
|
<node name="sitl_$(arg ID)" pkg="px4" type="px4" output="screen" args="$(find px4)/build/px4_sitl_default/etc -s etc/init.d-posix/rcS -i $(arg ID) -w sitl_$(arg vehicle)_$(arg ID) $(arg px4_command_arg1)">
|
|
</node>
|
|
<!-- spawn vehicle -->
|
|
<node name="$(arg vehicle)_$(arg ID)_spawn" output="screen" pkg="gazebo_ros" type="spawn_model" args="-sdf -param model_description -model $(arg vehicle)_$(arg ID) -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>
|
|
</launch>
|