-
Notifications
You must be signed in to change notification settings - Fork 0
/
mav_obstacle_rpyt.launch
132 lines (119 loc) · 7.91 KB
/
mav_obstacle_rpyt.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
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
<launch>
<arg name="node_start_delay" default="5.0" />
<arg name="mav_name" default="hummingbird"/>
<arg name="world_name" default="obstacle_wall"/>
<arg name="enable_logging" default="false" />
<arg name="enable_ground_truth" default="true" />
<arg name="log_file" default="$(arg mav_name)" />
<arg name="debug" default="false"/>
<arg name="gui" default="true"/>
<arg name="paused" default="false"/>
<!-- The following line causes gzmsg and gzerr messages to be printed to the console
(even when Gazebo is started through roslaunch) -->
<arg name="verbose" default="false"/>
<env name="GAZEBO_MODEL_PATH" value="${GAZEBO_MODEL_PATH}:$(find rotors_gazebo)/models"/>
<env name="GAZEBO_RESOURCE_PATH" value="${GAZEBO_RESOURCE_PATH}:$(find rotors_gazebo)/models"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find rotors_gazebo)/worlds/$(arg world_name).world" />
<arg name="debug" value="$(arg debug)" />
<arg name="paused" value="$(arg paused)" />
<arg name="gui" value="$(arg gui)" />
<arg name="verbose" value="$(arg verbose)"/>
</include>
<group ns="$(arg mav_name)1">
<include file="$(find rotors_gazebo)/launch/spawn_mav.launch">
<arg name="mav_name" value="$(arg mav_name)" />
<arg name="namespace" value="$(arg mav_name)1" />
<arg name="model" value="$(find rotors_description)/urdf/mav_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="$(arg log_file)1"/>
<arg name="x" value="0.0"/>
<arg name="y" value="3.5"/>
</include>
<node name="roll_pitch_yawrate_thrust_controller_node" pkg="rotors_control" type="roll_pitch_yawrate_thrust_controller_node" output="screen">
<rosparam command="load" file="$(find rotors_gazebo)/resource/roll_pitch_yawrate_thrust_controller_hummingbird.yaml" />
<rosparam command="load" file="$(find rotors_gazebo)/resource/$(arg mav_name).yaml" />
<remap from="odometry" to="odometry_sensor1/odometry" />
</node>
<node name="hovering_example" pkg="rotors_gazebo" type="hovering_example" output="screen"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="traj" pkg="potentialfield3d" type="hummingbird.py" output="screen">
<param name="traj_path" type="string" value="/home/yifan/catkin_ws/src/Dsp/generated_path/path_12.txt"/>
</node>
<node name="takeoff" pkg="rostopic" type="rostopic" args="pub /hummingbird1/set_start std_msgs/String 'data:'go''" launch-prefix="bash -c 'sleep $(arg node_start_delay); $0 $@' "/>
</group>
<group ns="$(arg mav_name)2">
<include file="$(find rotors_gazebo)/launch/spawn_mav.launch">
<arg name="mav_name" value="$(arg mav_name)" />
<arg name="namespace" value="$(arg mav_name)2" />
<arg name="model" value="$(find rotors_description)/urdf/mav_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="$(arg log_file)2"/>
<arg name="x" value="1.0"/>
<arg name="y" value="3.5"/>
</include>
<node name="roll_pitch_yawrate_thrust_controller_node" pkg="rotors_control" type="roll_pitch_yawrate_thrust_controller_node" output="screen">
<rosparam command="load" file="$(find rotors_gazebo)/resource/roll_pitch_yawrate_thrust_controller_hummingbird.yaml" />
<rosparam command="load" file="$(find rotors_gazebo)/resource/$(arg mav_name).yaml" />
<remap from="odometry" to="odometry_sensor1/odometry" />
</node>
<node name="hovering_example" pkg="rotors_gazebo" type="hovering_example" output="screen"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="traj" pkg="potentialfield3d" type="hummingbird2.py" output="screen">
<param name="traj_path" type="string" value="/home/yifan/catkin_ws/src/Dsp/generated_path/path_21.txt"/>
</node>
<node name="takeoff" pkg="rostopic" type="rostopic" args="pub /hummingbird2/set_start std_msgs/String 'data:'go''" launch-prefix="bash -c 'sleep $(arg node_start_delay); $0 $@' "/>
</group>
<group ns="$(arg mav_name)3">
<include file="$(find rotors_gazebo)/launch/spawn_mav.launch">
<arg name="mav_name" value="$(arg mav_name)" />
<arg name="namespace" value="$(arg mav_name)3" />
<arg name="model" value="$(find rotors_description)/urdf/mav_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="$(arg log_file)3"/>
<arg name="x" value="2.0"/>
<arg name="y" value="3.5"/>
</include>
<node name="roll_pitch_yawrate_thrust_controller_node" pkg="rotors_control" type="roll_pitch_yawrate_thrust_controller_node" output="screen">
<rosparam command="load" file="$(find rotors_gazebo)/resource/roll_pitch_yawrate_thrust_controller_hummingbird.yaml" />
<rosparam command="load" file="$(find rotors_gazebo)/resource/$(arg mav_name).yaml" />
<remap from="odometry" to="odometry_sensor1/odometry" />
</node>
<node name="hovering_example" pkg="rotors_gazebo" type="hovering_example" output="screen"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="traj" pkg="potentialfield3d" type="hummingbird3.py" output="screen">
<param name="traj_path" type="string" value="/home/yifan/catkin_ws/src/Dsp/generated_path/path_33.txt"/>
</node>
<node name="takeoff" pkg="rostopic" type="rostopic" args="pub /hummingbird3/set_start std_msgs/String 'data:'go''" launch-prefix="bash -c 'sleep $(arg node_start_delay); $0 $@' "/>
</group>
<group ns="$(arg mav_name)4">
<include file="$(find rotors_gazebo)/launch/spawn_mav.launch">
<arg name="mav_name" value="$(arg mav_name)" />
<arg name="namespace" value="$(arg mav_name)4" />
<arg name="model" value="$(find rotors_description)/urdf/mav_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="$(arg log_file)4"/>
<arg name="x" value="3.0"/>
<arg name="y" value="3.5"/>
</include>
<node name="roll_pitch_yawrate_thrust_controller_node" pkg="rotors_control" type="roll_pitch_yawrate_thrust_controller_node" output="screen">
<rosparam command="load" file="$(find rotors_gazebo)/resource/roll_pitch_yawrate_thrust_controller_hummingbird.yaml" />
<rosparam command="load" file="$(find rotors_gazebo)/resource/$(arg mav_name).yaml" />
<remap from="odometry" to="odometry_sensor1/odometry" />
</node>
<node name="hovering_example" pkg="rotors_gazebo" type="hovering_example" output="screen"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="traj" pkg="potentialfield3d" type="hummingbird4.py" output="screen">
<param name="traj_path" type="string" value="/home/yifan/catkin_ws/src/Dsp/generated_path/path_44.txt"/>
</node>
<node name="takeoff" pkg="rostopic" type="rostopic" args="pub /hummingbird4/set_start std_msgs/String 'data:'go''" launch-prefix="bash -c 'sleep $(arg node_start_delay); $0 $@' "/>
</group>
</launch>