-
Notifications
You must be signed in to change notification settings - Fork 75
/
single_drone_planner.xml
277 lines (247 loc) · 16 KB
/
single_drone_planner.xml
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
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
<launch>
<arg name="map_size_x"/>
<arg name="map_size_y"/>
<arg name="map_size_z"/>
<arg name="drone_id"/>
<arg name="drone_num"/>
<arg name="odometry_topic"/>
<arg name="sensor_pose_topic"/>
<arg name="depth_topic"/>
<arg name="cloud_topic"/>
<arg name="cx"/>
<arg name="cy"/>
<arg name="fx"/>
<arg name="fy"/>
<arg name="max_vel"/>
<arg name="max_acc"/>
<arg name="simulation" default="true"/>
<arg name="single_expo" default="false"/>
<!-- main node -->
<node pkg="exploration_manager" name="exploration_node_$(arg drone_id)" type="exploration_node" output="log">
<remap from ="/odom_world" to="$(arg odometry_topic)"/>
<remap from ="/map_ros/pose" to = "$(arg sensor_pose_topic)"/>
<remap from ="/map_ros/depth" to = "$(arg depth_topic)"/>
<remap from ="/map_ros/cloud" to="$(arg cloud_topic)"/>
<remap from="/planning/replan" to="/planning/replan_$(arg drone_id)" />
<remap from="/planning/new" to="/planning/new_$(arg drone_id)" />
<remap from="/planning/bspline" to="/planning/bspline_$(arg drone_id)" />
<remap from="/swarm_expl/drone_state_send" to="/swarm_expl/drone_state" />
<remap from="/swarm_expl/drone_state_recv" to="/swarm_expl/drone_state" />
<remap from="/swarm_expl/pair_opt_send" to="/swarm_expl/pair_opt" />
<remap from="/swarm_expl/pair_opt_recv" to="/swarm_expl/pair_opt" />
<remap from="/swarm_expl/pair_opt_res_send" to="/swarm_expl/pair_opt_res" />
<remap from="/swarm_expl/pair_opt_res_recv" to="/swarm_expl/pair_opt_res" />
<remap from="/swarm_expl/grid_tour_send" to="/swarm_expl/grid_tour" />
<remap from="/swarm_expl/hgrid_send" to="/swarm_expl/hgrid" />
<remap from="/multi_map_manager/chunk_stamps_send" to="/multi_map_manager/chunk_stamps" />
<remap from="/multi_map_manager/chunk_data_send" to="/multi_map_manager/chunk_data" />
<remap from="/multi_map_manager/chunk_stamps_recv" to="/multi_map_manager/chunk_stamps" />
<remap from="/multi_map_manager/chunk_data_recv" to="/multi_map_manager/chunk_data" />
<remap from="/planning/swarm_traj_recv" to="/planning/swarm_traj" />
<remap from="/planning/swarm_traj_send" to="/planning/swarm_traj" />
<remap from="/planning_vis/trajectory" to="/planning_vis/trajectory_$(arg drone_id)" />
<remap from="/planning_vis/frontier" to="/planning_vis/frontier_$(arg drone_id)" />
<remap from="/planning_vis/viewpoints" to="/planning_vis/viewpoints_$(arg drone_id)" />
<remap from="/sdf_map/occupancy_all" to="/sdf_map/occupancy_all_$(arg drone_id)" />
<remap from="/sdf_map/occupancy_local" to="/sdf_map/occupancy_local_$(arg drone_id)" />
<remap from="/sdf_map/occupancy_local_inflate" to="/sdf_map/occupancy_local_inflate_$(arg drone_id)" />
<remap from="/sdf_map/unknown" to="/sdf_map/unknown_$(arg drone_id)" />
<remap from="/sdf_map/update_range" to="/sdf_map/update_range_$(arg drone_id)" />
<remap from="/sdf_map/basecoor" to="/swarm_sim_tf/basecoor_$(arg drone_id)" if="$(arg simulation)"/>
<remap from="/sdf_map/basecoor" to="/swarm_drones/swarm_drone_basecoor" unless="$(arg simulation)"/>
<param name="sdf_map/resolution" value="0.1" />
<param name="sdf_map/map_size_x" value="$(arg map_size_x)" />
<param name="sdf_map/map_size_y" value="$(arg map_size_y)" />
<param name="sdf_map/map_size_z" value="$(arg map_size_z)" />
<param name="sdf_map/obstacles_inflation" value="0.199" />
<!-- <param name="sdf_map/obstacles_inflation" value="0.0" /> -->
<param name="sdf_map/local_bound_inflate" value="0.5"/>
<param name="sdf_map/local_map_margin" value="50"/>
<param name="sdf_map/ground_height" value="-1.0"/>
<param name="sdf_map/default_dist" value="0.5"/>
<param name="sdf_map/p_hit" value="0.65"/>
<param name="sdf_map/p_miss" value="0.35"/>
<param name="sdf_map/p_min" value="0.12"/>
<param name="sdf_map/p_max" value="0.90"/>
<param name="sdf_map/p_occ" value="0.80"/>
<param name="sdf_map/min_ray_length" value="0.5"/>
<param name="sdf_map/max_ray_length" value="4.5"/>
<param name="sdf_map/virtual_ceil_height" value="-10"/>
<param name="sdf_map/optimistic" value="true" type="bool"/>
<param name="sdf_map/signed_dist" value="false" type="bool"/>
<!-- <param name="sdf_map/box_min_x" value="-4" type="double"/>
<param name="sdf_map/box_min_y" value="-7" type="double"/>
<param name="sdf_map/box_min_z" value="0.0" type="double"/>
<param name="sdf_map/box_max_x" value="4" type="double"/>
<param name="sdf_map/box_max_y" value="7" type="double"/>
<param name="sdf_map/box_max_z" value="2.0" type="double"/> -->
<param name="sdf_map/box_min_x" value="-7" type="double"/>
<param name="sdf_map/box_min_y" value="-15" type="double"/>
<param name="sdf_map/box_min_z" value="0" type="double"/>
<param name="sdf_map/box_max_x" value="7" type="double"/>
<param name="sdf_map/box_max_y" value="15" type="double"/>
<param name="sdf_map/box_max_z" value="1.7" type="double"/>
<param name="sdf_map/no_drone_1" value="false" type="bool"/>
<param name="map_ros/cx" value="$(arg cx)"/>
<param name="map_ros/cy" value="$(arg cy)"/>
<param name="map_ros/fx" value="$(arg fx)"/>
<param name="map_ros/fy" value="$(arg fy)"/>
<param name="map_ros/depth_filter_maxdist" value="4.6"/>
<param name="map_ros/depth_filter_mindist" value="0.2"/>
<param name="map_ros/depth_filter_margin" value="2"/>
<param name="map_ros/k_depth_scaling_factor" value="1000.0"/>
<param name="map_ros/skip_pixel" value="2"/>
<param name="map_ros/esdf_slice_height" value="0.5"/>
<param name="map_ros/visualization_truncate_height" value="10.09"/>
<param name="map_ros/visualization_truncate_low" value="-2.0"/>
<param name="map_ros/show_occ_time" value="false"/>
<param name="map_ros/show_esdf_time" value="false"/>
<param name="map_ros/show_all_map" value="true"/>
<param name="map_ros/frame_id" value="world"/>
<!-- Fsm -->
<param name="fsm/thresh_replan1" value="0.2" type="double"/>
<param name="fsm/thresh_replan2" value="0.2" type="double"/>
<param name="fsm/thresh_replan3" value="1.5" type="double"/>
<!-- <param name="fsm/thresh_replan1" value="0.00001" type="double"/> -->
<!-- <param name="fsm/thresh_replan2" value="100.0" type="double"/> -->
<!-- <param name="fsm/thresh_replan3" value="0.1" type="double"/> -->
<param name="fsm/replan_time" value="0.200" type="double"/>
<param name="fsm/sync_interval" value="0.200" type="double"/>
<param name="fsm/wait_delete_duration" value="0.05" type="double"/>
<param name="fsm/gain_thresh" value="10" type="int"/>
<param name="fsm/attempt_interval" value="0.1" type="double"/>
<param name="fsm/pair_opt_interval" value="0.5" type="double"/>
<param name="partitioning/min_unknown" value="4000" type="int"/>;
<param name="partitioning/min_frontier" value="100" type="int"/>;
<param name="partitioning/min_free" value="3000" type="int"/>;
<param name="partitioning/consistent_cost" value="-5" type="double"/>;
<param name="partitioning/consistent_cost2" value="8" type="double"/>;
<param name="partitioning/w_unknown" value="0.0" type="double"/>;
<param name="partitioning/grid_size" value="5.0" type="double"/>;
<param name="partitioning/use_swarm_tf" value="true" type="bool"/>;
<!-- Exploration manager -->
<param name="exploration/refine_local" value="true" type="bool"/>
<param name="exploration/refined_num" value="7" type="int"/>
<param name="exploration/refined_radius" value="5.0" type="double"/>
<param name="exploration/max_decay" value="0.8" type="double"/>
<param name="exploration/top_view_num" value="15" type="int"/>
<param name="exploration/vm" value="$(eval 1.0 * arg('max_vel'))" type="double"/>
<param name="exploration/am" value="$(eval 1.0 * arg('max_acc'))" type="double"/>
<param name="exploration/yd" value="$(eval 80 * 3.1415926 / 180.0)" type="double"/>
<!-- <param name="exploration/yd" value="$(eval 60 * 3.1415926 / 180.0)" type="double"/> -->
<param name="exploration/ydd" value="$(eval 90 * 3.1415926 / 180.0)" type="double"/>
<param name="exploration/w_dir" value="1.5" type="double"/>
<param name="exploration/tsp_dir" value="$(find lkh_tsp_solver)/resource" type="string"/>
<param name="exploration/mtsp_dir" value="$(find lkh_mtsp_solver)/resource" type="string"/>
<param name="exploration/drone_num" value="$(arg drone_num)" type="double"/>
<param name="exploration/drone_id" value="$(arg drone_id)" type="int"/>
<param name="exploration/init_plan_num" value="2" type="int"/>
<param name="frontier/cluster_min" value="100" type="int"/>
<param name="frontier/cluster_size_xy" value="2.0" type="double"/>
<param name="frontier/cluster_size_z" value="10.0" type="double"/>
<param name="frontier/min_candidate_dist" value="0.5" type="double"/>
<param name="frontier/min_candidate_clearance" value="0.21" type="double"/>
<param name="frontier/candidate_dphi" value="$(eval 15 * 3.1415926 / 180.0)" type="double"/>
<param name="frontier/candidate_rnum" value="3" type="int"/>
<param name="frontier/candidate_rmin" value="1.0" type="double"/>
<param name="frontier/candidate_rmax" value="1.5" type="double"/>
<param name="frontier/down_sample" value="3" type="int"/>;
<param name="frontier/min_visib_num" value="30" type="int"/>;
<param name="frontier/min_view_finish_fraction" value="0.2" type="double"/>;
<!-- Perception utils -->
<param name="perception_utils/top_angle" value="0.56125" type="double"/>;
<param name="perception_utils/left_angle" value="0.69222" type="double"/>;
<param name="perception_utils/right_angle" value="0.68901" type="double"/>;
<param name="perception_utils/max_dist" value="4.5" type="double"/>;
<param name="perception_utils/vis_dist" value="1.0" type="double"/>;
<param name="heading_planner/yaw_diff" value="$(eval 30 * 3.1415926 / 180.0)" type="double"/>
<param name="heading_planner/half_vert_num" value="5" type="int"/>
<param name="heading_planner/lambda1" value="2.0" type="double"/>
<param name="heading_planner/lambda2" value="1.0" type="double"/>
<param name="heading_planner/max_yaw_rate" value="$(eval 10 * 3.1415926 / 180.0)" type="double"/>
<param name="heading_planner/w" value="20000.0" type="double"/>
<param name="heading_planner/weight_type" value="1" type="double"/>
<!-- planner manager -->
<!-- <param name="manager/max_vel" value="$(arg max_vel)" type="double"/> -->
<param name="manager/max_vel" value="$(arg max_vel)" type="double"/>
<param name="manager/max_acc" value="$(arg max_acc)" type="double"/>
<param name="manager/max_jerk" value="4" type="double"/>
<param name="manager/dynamic_environment" value="0" type="int"/>
<param name="manager/local_segment_length" value="6.0" type="double"/>
<param name="manager/clearance_threshold" value="0.2" type="double"/>
<param name="manager/control_points_distance" value="0.5" type="double"/>
<param name="manager/use_geometric_path" value="true" type="bool"/>
<param name="manager/use_kinodynamic_path" value="true" type="bool"/>
<param name="manager/use_topo_path" value="false" type="bool"/>
<param name="manager/use_optimization" value="true" type="bool"/>
<param name="manager/use_active_perception" value="true" type="bool"/>
<param name="manager/min_time" value="true" type="bool"/>
<param name="manager/relax_time1" value="0.3" type="double"/>
<param name="manager/relax_time2" value="1.5" type="double"/>
<param name="manager/max_yawdot" value="$(eval 120 * 3.1415926 / 180.0)" type="double"/>
<!-- kinodynamic path searching -->
<param name="search/max_tau" value="0.8" type="double"/>
<param name="search/init_max_tau" value="1.0" type="double"/>
<param name="search/max_vel" value="$(arg max_vel)" type="double"/>
<param name="search/vel_margin" value="0.25" type="double"/>
<param name="search/max_acc" value="$(arg max_acc)" type="double"/>
<param name="search/w_time" value="10.0" type="double"/>
<param name="search/horizon" value="5.0" type="double"/>
<param name="search/lambda_heu" value="10.0" type="double"/>
<param name="search/resolution_astar" value="0.025" type="double"/>
<param name="search/time_resolution" value="0.8" type="double"/>
<param name="search/margin" value="0.2" type="double"/>
<param name="search/allocate_num" value="100000" type="int"/>
<param name="search/check_num" value="10" type="int"/>
<param name="search/optimistic" value="false" type="bool"/>
<param name="astar/lambda_heu" value="10000.0" type="double"/>
<param name="astar/resolution_astar" value="0.3" type="double"/>
<param name="astar/allocate_num" value="1000000" type="int"/>
<param name="astar/max_search_time" value="0.001" type="double"/>
<!-- trajectory optimization -->
<param name="optimization/ld_smooth" value="5.0" type="double"/>
<param name="optimization/ld_dist" value="10.0" type="double"/>
<param name="optimization/ld_feasi" value="2.0" type="double"/>
<param name="optimization/ld_start" value="100.0" type="double"/>
<param name="optimization/ld_end" value="0.5" type="double"/>
<param name="optimization/ld_guide" value="1.5" type="double"/>
<param name="optimization/ld_waypt" value="7.0" type="double"/>
<param name="optimization/ld_view" value="0.0" type="double"/>
<param name="optimization/ld_time" value="1.5" type="double"/>
<param name="optimization/ld_swarm" value="5.0" type="double"/>
<param name="optimization/swarm_safe_dist" value="1.0" type="double"/>
<param name="optimization/dist0" value="0.7" type="double"/>
<param name="optimization/max_vel" value="$(arg max_vel)" type="double"/>
<param name="optimization/max_acc" value="$(arg max_acc)" type="double"/>
<param name="optimization/algorithm1" value="15" type="int"/>
<param name="optimization/algorithm2" value="11" type="int"/>
<param name="optimization/max_iteration_num1" value="2" type="int"/>
<param name="optimization/max_iteration_num2" value="2000" type="int"/>
<param name="optimization/max_iteration_num3" value="200" type="int"/>
<param name="optimization/max_iteration_num4" value="200" type="int"/>
<param name="optimization/max_iteration_time1" value="0.0001" type="double"/>
<param name="optimization/max_iteration_time2" value="0.005" type="double"/>
<param name="optimization/max_iteration_time3" value="0.003" type="double"/>
<param name="optimization/max_iteration_time4" value="0.003" type="double"/>
<param name="bspline/limit_vel" value="$(arg max_vel)" type="double"/>
<param name="bspline/limit_acc" value="$(arg max_acc)" type="double"/>
<param name="bspline/limit_ratio" value="1.1" type="double"/>
<param name="bspline/limit_vel" value="$(arg max_vel)" type="double"/>
<param name="bspline/limit_acc" value="$(arg max_acc)" type="double"/>
<param name="bspline/limit_ratio" value="1.1" type="double"/>
</node>
<!-- <node pkg="lkh_tsp_solver" name="tsp_solver_$(arg drone_id)" type="tsp_node" output="screen">
<param name="exploration/drone_id" value="$(arg drone_id)" type="int"/>
<param name="exploration/tsp_dir" value="$(find lkh_tsp_solver)/resource" type="string"/>
</node> -->
<node pkg="lkh_mtsp_solver" name="tsp_solver_$(arg drone_id)" type="mtsp_node" output="log">
<param name="exploration/drone_id" value="$(arg drone_id)" type="int"/>
<param name="exploration/mtsp_dir" value="$(find lkh_mtsp_solver)/resource" type="string"/>
<param name="exploration/problem_id" value="1" type="int"/>
</node>
<node pkg="lkh_mtsp_solver" name="acvrp_solver_$(arg drone_id)" type="mtsp_node" output="log">
<param name="exploration/drone_id" value="$(arg drone_id)" type="int"/>
<param name="exploration/mtsp_dir" value="$(find lkh_mtsp_solver)/resource" type="string"/>
<param name="exploration/problem_id" value="2" type="int"/>
</node>
</launch>