forked from PX4/rotors_simulator
-
Notifications
You must be signed in to change notification settings - Fork 6
/
three_multicopters_hovering_example.launch
69 lines (64 loc) · 3.46 KB
/
three_multicopters_hovering_example.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
58
59
60
61
62
63
64
65
66
67
68
69
<launch>
<arg name="enable_logging" default="false"/>
<arg name="enable_ground_truth" default="true"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find rotors_gazebo)/worlds/basic.world"/>
<!-- <arg name="debug" value="true"/> -->
<arg name="paused" value="true"/>
<!-- <arg name="gui" value="false"/> -->
</include>
<group ns="hummingbird">
<rosparam param="wp_x">0</rosparam>
<rosparam param="wp_y">0</rosparam>
<rosparam param="wp_z">1</rosparam>
<include file="$(find rotors_gazebo)/launch/spawn_hummingbird.launch">
<arg name="model" value="$(find rotors_description)/urdf/hummingbird_generic_odometry_sensor.gazebo" />
<arg name="enable_logging" value="$(arg enable_logging)" />
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
<arg name="log_file" value="hummingbird"/>
<arg name="y" value="0.0"/>
</include>
<node name="lee_position_controller_node" pkg="rotors_control" type="lee_position_controller_node" output="screen">
<rosparam command="load" file="$(find rotors_gazebo)/resource/lee_controller_hummingbird.yaml" />
<rosparam command="load" file="$(find rotors_gazebo)/resource/hummingbird.yaml" />
<remap from="odometry" to="odometry_sensor1/odometry" />
</node>
<node name="hovering_example" pkg="rotors_gazebo" type="hovering_example" output="screen"/>
</group>
<group ns="pelican">
<rosparam param="wp_x">0</rosparam>
<rosparam param="wp_y">1</rosparam>
<rosparam param="wp_z">1</rosparam>
<include file="$(find rotors_gazebo)/launch/spawn_pelican.launch">
<arg name="model" value="$(find rotors_description)/urdf/pelican_generic_odometry_sensor.gazebo" />
<arg name="enable_logging" value="$(arg enable_logging)" />
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
<arg name="log_file" value="pelican"/>
<arg name="y" value="1.0"/>
</include>
<node name="lee_position_controller_node" pkg="rotors_control" type="lee_position_controller_node" output="screen">
<rosparam command="load" file="$(find rotors_gazebo)/resource/lee_controller_pelican.yaml" />
<rosparam command="load" file="$(find rotors_gazebo)/resource/pelican.yaml" />
<remap from="odometry" to="odometry_sensor1/odometry" />
</node>
<node name="hovering_example" pkg="rotors_gazebo" type="hovering_example"/>
</group>
<group ns="firefly">
<rosparam param="wp_x">0</rosparam>
<rosparam param="wp_y">2</rosparam>
<rosparam param="wp_z">1</rosparam>
<include file="$(find rotors_gazebo)/launch/spawn_firefly.launch">
<arg name="model" value="$(find rotors_description)/urdf/firefly_generic_odometry_sensor.gazebo" />
<arg name="enable_logging" value="$(arg enable_logging)" />
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
<arg name="log_file" value="firefly"/>
<arg name="y" value="2.0"/>
</include>
<node name="lee_position_controller_node" pkg="rotors_control" type="lee_position_controller_node" output="screen">
<rosparam command="load" file="$(find rotors_gazebo)/resource/lee_controller_firefly.yaml" />
<rosparam command="load" file="$(find rotors_gazebo)/resource/firefly.yaml" />
<remap from="odometry" to="odometry_sensor1/odometry" />
</node>
<node name="hovering_example" pkg="rotors_gazebo" type="hovering_example" output="screen"/>
</group>
</launch>