mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
- new modules/simulation directory to collect all simulators and related modules - new Tools/simulation directory to collect and organize scattered simulation submodules, scripts, etc - simulation module renamed to simulator_mavlink - sih renamed to simulator_sih (not a great name, but I wanted to be clear it was a simulator) - ignition_simulator renamed to simulator_ignition_bridge - large sitl_target.cmake split by simulation option and in some cases pushed to appropriate modules - sitl targets broken down to what's actually available (eg jmavsim only has 1 model and 1 world) - new Gazebo consistently referred to as Ignition for now (probably the least confusing thing until we fully drop Gazebo classic support someday)
36 lines
2.1 KiB
XML
36 lines
2.1 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"/>
|
|
<!-- 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)" />
|
|
<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>
|