single_vehicle_spawn.launch 2.13 KB
<?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"/>
    <!-- vehicle model and config -->
    <arg name="est" default="ekf2"/>
    <arg name="vehicle" default="iris"/>
    <arg name="ID" default="1"/>
    <env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
    <env name="PX4_ESTIMATOR" value="$(arg est)" />
    <arg name="mavlink_udp_port" default="14560"/>
    <arg name="mavlink_tcp_port" default="4560"/>
    <arg name="gst_udp_port" default="5600"/>
    <arg name="video_uri" default="5600"/>
    <arg name="mavlink_cam_udp_port" default="14530"/>
    <arg name="mavlink_id" value="$(eval 1 + arg('ID'))" />
    <!-- PX4 configs -->
    <arg name="interactive" default="true"/>
    <!-- generate sdf vehicle model -->
    <arg name="cmd" default="$(find mavlink_sitl_gazebo)/scripts/jinja_gen.py --stdout --mavlink_id=$(arg mavlink_id) --mavlink_udp_port=$(arg mavlink_udp_port) --mavlink_tcp_port=$(arg mavlink_tcp_port) --gst_udp_port=$(arg gst_udp_port) --video_uri=$(arg video_uri) --mavlink_cam_udp_port=$(arg mavlink_cam_udp_port) $(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf.jinja $(find mavlink_sitl_gazebo)"/>
    <param command="$(arg cmd)" name="sdf_$(arg vehicle)$(arg ID)"/>
    <!-- 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="$(anon vehicle_spawn)" pkg="gazebo_ros" type="spawn_model" output="screen" args="-sdf -param sdf_$(arg vehicle)$(arg ID) -model $(arg vehicle)$(arg ID) -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>
</launch>