|
|
@ -19,14 +19,14 @@ |
|
|
|
<arg name="mavlink_tcp_port" default="4560"/> |
|
|
|
<arg name="mavlink_tcp_port" default="4560"/> |
|
|
|
<!-- PX4 configs --> |
|
|
|
<!-- PX4 configs --> |
|
|
|
<arg name="interactive" default="true"/> |
|
|
|
<arg name="interactive" default="true"/> |
|
|
|
<!-- generate urdf vehicle model --> |
|
|
|
<!-- generate sdf vehicle model --> |
|
|
|
<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) mavlink_tcp_port:=$(arg mavlink_tcp_port) --inorder"/> |
|
|
|
<arg name="cmd" default="$(find mavlink_sitl_gazebo)/scripts/jinja_gen.py --stdout --mavlink_udp_port=$(arg mavlink_udp_port) --mavlink_tcp_port=$(arg mavlink_tcp_port) $(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf.jinja $(find mavlink_sitl_gazebo)"/> |
|
|
|
<param command="$(arg cmd)" name="rotors_description"/> |
|
|
|
<param command="$(arg cmd)" name="sdf_$(arg vehicle)$(arg ID)"/> |
|
|
|
<!-- PX4 SITL --> |
|
|
|
<!-- PX4 SITL --> |
|
|
|
<arg unless="$(arg interactive)" name="px4_command_arg1" value=""/> |
|
|
|
<arg unless="$(arg interactive)" name="px4_command_arg1" value=""/> |
|
|
|
<arg if="$(arg interactive)" name="px4_command_arg1" value="-d"/> |
|
|
|
<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 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> |
|
|
|
</node> |
|
|
|
<!-- spawn vehicle --> |
|
|
|
<!-- spawn vehicle --> |
|
|
|
<node name="$(arg vehicle)_$(arg ID)_spawn" output="screen" pkg="gazebo_ros" type="spawn_model" 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)"/> |
|
|
|
<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> |
|
|
|
</launch> |
|
|
|