-
Notifications
You must be signed in to change notification settings - Fork 272
/
Copy pathsimulator.launch
57 lines (51 loc) · 3.14 KB
/
simulator.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
<launch>
<arg name="type" default="gazebo"/> <!-- gazebo, jmavsim, none (only clover packages) -->
<arg name="mav_id" default="0"/>
<arg name="est" default="ekf2"/> <!-- PX4 estimator: lpe, ekf2 -->
<arg name="vehicle" default="clover"/> <!-- PX4 vehicle configuration: clover, clover_vpe -->
<arg name="main_camera" default="true"/> <!-- Simulated vision position estimation camera (optical flow, ArUco) -->
<arg name="maintain_camera_rate" default="false"/> <!-- Slow simulation down to maintain camera rate -->
<arg name="rangefinder" default="true"/> <!-- Simulated downward-facing rangefinder, vl53l1x-like -->
<arg name="led" default="true"/> <!-- Simulated LED strip, ws281x-like -->
<arg name="gps" default="false"/> <!--Simulated GPS module -->
<arg name="use_clover_physics" default="false"/> <!-- Use inertial parameters from CAD models -->
<arg name="gui" default="true"/> <!-- Run Gazebo with GUI -->
<!-- Gazebo instance -->
<include file="$(find gazebo_ros)/launch/empty_world.launch" if="$(eval type == 'gazebo')">
<!-- Workaround for crashes in VMware -->
<env name="SVGA_VGPU10" value="0"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="world_name" value="$(find clover_simulation)/resources/worlds/clover_aruco.world"/>
<arg name="verbose" value="true"/>
</include>
<!-- PX4 instance -->
<node name="sitl_$(arg mav_id)" pkg="px4" type="px4" output="screen" required="true" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg mav_id)" unless="$(eval type == 'none')">
<env name="PX4_SIM_MODEL" value="$(arg vehicle)"/>
<env name="PX4_ESTIMATOR" value="$(arg est)"/>
</node>
<!-- Clover model -->
<include file="$(find clover_description)/launch/spawn_drone.launch" if="$(eval type == 'gazebo')">
<arg name="main_camera" value="$(arg main_camera)"/>
<arg name="maintain_camera_rate" value="$(arg maintain_camera_rate)"/>
<arg name="rangefinder" value="$(arg rangefinder)"/>
<arg name="led" value="$(arg led)"/>
<arg name="gps" value="$(arg gps)"/>
<arg name="use_clover_physics" value="$(arg use_clover_physics)"/>
</include>
<node name="jmavsim" pkg="px4" required="true" type="jmavsim_run.sh" output="screen" if="$(eval type == 'jmavsim')">
<env name="HEADLESS" value="1" if="$(eval not gui)"/>
</node>
<param name="use_sim_time" value="false" if="$(eval type == 'jmavsim')"/>
<!-- Clover services -->
<include file="$(find clover)/launch/clover.launch">
<arg name="simulator" value="true"/>
<arg name="fcu_conn" value="sitl"/>
<arg name="fcu_ip" value="127.0.0.1"/>
<arg name="gcs_bridge" value=""/>
<arg name="web_video_server" default="false" if="$(eval type == 'jmavsim')"/>
<arg name="main_camera" default="false" if="$(eval type == 'jmavsim')"/>
<arg name="aruco" default="false" if="$(eval type == 'jmavsim')"/>
<arg name="optical_flow" default="false" if="$(eval type == 'jmavsim')"/>
<arg name="led" default="false" if="$(eval type == 'jmavsim')"/>
</include>
</launch>