full_planner_test.cpp
Go to the documentation of this file.
1 
2 /*
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2018, Locus Robotics
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the copyright holder nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 #include <global_planner_tests/many_map_test_suite.h>
37 #include <ros/ros.h>
38 #include <gtest/gtest.h>
39 #include <memory>
40 #include <string>
41 
42 using global_planner_tests::many_map_test_suite;
44 
45 
46 TEST(GlobalPlanner, DijkstraVonNeumann)
47 {
48  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
49  DluxGlobalPlanner planner;
50  std::string ns = "DijkstraVonNeumann";
51 
52  ros::NodeHandle nh("~/" + ns);
53  nh.setParam("planner/potential_calculator", "dlux_plugins::Dijkstra");
54  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
55  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
56 }
57 
58 
59 TEST(GlobalPlanner, DijkstraGrid)
60 {
61  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
62  DluxGlobalPlanner planner;
63  std::string ns = "DijkstraGrid";
64 
65  ros::NodeHandle nh("~/" + ns);
66  nh.setParam("planner/potential_calculator", "dlux_plugins::Dijkstra");
67  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
68  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
69 }
70 
71 
72 TEST(GlobalPlanner, DijkstraGradientStep)
73 {
74  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
75  DluxGlobalPlanner planner;
76  std::string ns = "DijkstraGradientStep";
77 
78  ros::NodeHandle nh("~/" + ns);
79  nh.setParam("planner/potential_calculator", "dlux_plugins::Dijkstra");
80  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
81  nh.setParam("planner/grid_step_near_high", true);
82  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
83 }
84 
85 
86 TEST(GlobalPlanner, DijkstraGradient)
87 {
88  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
89  DluxGlobalPlanner planner;
90  std::string ns = "DijkstraGradient";
91 
92  ros::NodeHandle nh("~/" + ns);
93  nh.setParam("planner/potential_calculator", "dlux_plugins::Dijkstra");
94  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
95  nh.setParam("planner/grid_step_near_high", false);
96  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
97 }
98 
99 
100 TEST(GlobalPlanner, AStarVonNeumannManK)
101 {
102  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
103  DluxGlobalPlanner planner;
104  std::string ns = "AStarVonNeumannManK";
105 
106  ros::NodeHandle nh("~/" + ns);
107  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
108  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
109  nh.setParam("planner/minimum_requeue_change", 0.0);
110  nh.setParam("planner/use_kernel", true);
111  nh.setParam("planner/manhattan_heuristic", true);
112  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
113 }
114 
115 
116 TEST(GlobalPlanner, AStarVonNeumannK)
117 {
118  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
119  DluxGlobalPlanner planner;
120  std::string ns = "AStarVonNeumannK";
121 
122  ros::NodeHandle nh("~/" + ns);
123  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
124  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
125  nh.setParam("planner/minimum_requeue_change", 0.0);
126  nh.setParam("planner/use_kernel", true);
127  nh.setParam("planner/manhattan_heuristic", false);
128  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
129 }
130 
131 
132 TEST(GlobalPlanner, AStarVonNeumannMan)
133 {
134  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
135  DluxGlobalPlanner planner;
136  std::string ns = "AStarVonNeumannMan";
137 
138  ros::NodeHandle nh("~/" + ns);
139  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
140  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
141  nh.setParam("planner/minimum_requeue_change", 0.0);
142  nh.setParam("planner/use_kernel", false);
143  nh.setParam("planner/manhattan_heuristic", true);
144  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
145 }
146 
147 
148 TEST(GlobalPlanner, AStarVonNeumann)
149 {
150  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
151  DluxGlobalPlanner planner;
152  std::string ns = "AStarVonNeumann";
153 
154  ros::NodeHandle nh("~/" + ns);
155  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
156  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
157  nh.setParam("planner/minimum_requeue_change", 0.0);
158  nh.setParam("planner/use_kernel", false);
159  nh.setParam("planner/manhattan_heuristic", false);
160  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
161 }
162 
163 
164 TEST(GlobalPlanner, AStarVonNeumannManThreshK)
165 {
166  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
167  DluxGlobalPlanner planner;
168  std::string ns = "AStarVonNeumannManThreshK";
169 
170  ros::NodeHandle nh("~/" + ns);
171  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
172  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
173  nh.setParam("planner/minimum_requeue_change", 1.0);
174  nh.setParam("planner/use_kernel", true);
175  nh.setParam("planner/manhattan_heuristic", true);
176  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
177 }
178 
179 
180 TEST(GlobalPlanner, AStarVonNeumannThreshK)
181 {
182  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
183  DluxGlobalPlanner planner;
184  std::string ns = "AStarVonNeumannThreshK";
185 
186  ros::NodeHandle nh("~/" + ns);
187  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
188  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
189  nh.setParam("planner/minimum_requeue_change", 1.0);
190  nh.setParam("planner/use_kernel", true);
191  nh.setParam("planner/manhattan_heuristic", false);
192  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
193 }
194 
195 
196 TEST(GlobalPlanner, AStarVonNeumannManThresh)
197 {
198  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
199  DluxGlobalPlanner planner;
200  std::string ns = "AStarVonNeumannManThresh";
201 
202  ros::NodeHandle nh("~/" + ns);
203  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
204  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
205  nh.setParam("planner/minimum_requeue_change", 1.0);
206  nh.setParam("planner/use_kernel", false);
207  nh.setParam("planner/manhattan_heuristic", true);
208  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
209 }
210 
211 
212 TEST(GlobalPlanner, AStarVonNeumannThresh)
213 {
214  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
215  DluxGlobalPlanner planner;
216  std::string ns = "AStarVonNeumannThresh";
217 
218  ros::NodeHandle nh("~/" + ns);
219  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
220  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
221  nh.setParam("planner/minimum_requeue_change", 1.0);
222  nh.setParam("planner/use_kernel", false);
223  nh.setParam("planner/manhattan_heuristic", false);
224  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
225 }
226 
227 
228 TEST(GlobalPlanner, AStarGridManK)
229 {
230  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
231  DluxGlobalPlanner planner;
232  std::string ns = "AStarGridManK";
233 
234  ros::NodeHandle nh("~/" + ns);
235  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
236  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
237  nh.setParam("planner/minimum_requeue_change", 0.0);
238  nh.setParam("planner/use_kernel", true);
239  nh.setParam("planner/manhattan_heuristic", true);
240  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
241 }
242 
243 
244 TEST(GlobalPlanner, AStarGridK)
245 {
246  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
247  DluxGlobalPlanner planner;
248  std::string ns = "AStarGridK";
249 
250  ros::NodeHandle nh("~/" + ns);
251  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
252  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
253  nh.setParam("planner/minimum_requeue_change", 0.0);
254  nh.setParam("planner/use_kernel", true);
255  nh.setParam("planner/manhattan_heuristic", false);
256  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
257 }
258 
259 
260 TEST(GlobalPlanner, AStarGridMan)
261 {
262  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
263  DluxGlobalPlanner planner;
264  std::string ns = "AStarGridMan";
265 
266  ros::NodeHandle nh("~/" + ns);
267  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
268  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
269  nh.setParam("planner/minimum_requeue_change", 0.0);
270  nh.setParam("planner/use_kernel", false);
271  nh.setParam("planner/manhattan_heuristic", true);
272  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
273 }
274 
275 
276 TEST(GlobalPlanner, AStarGrid)
277 {
278  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
279  DluxGlobalPlanner planner;
280  std::string ns = "AStarGrid";
281 
282  ros::NodeHandle nh("~/" + ns);
283  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
284  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
285  nh.setParam("planner/minimum_requeue_change", 0.0);
286  nh.setParam("planner/use_kernel", false);
287  nh.setParam("planner/manhattan_heuristic", false);
288  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
289 }
290 
291 
292 TEST(GlobalPlanner, AStarGridManThreshK)
293 {
294  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
295  DluxGlobalPlanner planner;
296  std::string ns = "AStarGridManThreshK";
297 
298  ros::NodeHandle nh("~/" + ns);
299  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
300  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
301  nh.setParam("planner/minimum_requeue_change", 1.0);
302  nh.setParam("planner/use_kernel", true);
303  nh.setParam("planner/manhattan_heuristic", true);
304  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
305 }
306 
307 
308 TEST(GlobalPlanner, AStarGridThreshK)
309 {
310  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
311  DluxGlobalPlanner planner;
312  std::string ns = "AStarGridThreshK";
313 
314  ros::NodeHandle nh("~/" + ns);
315  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
316  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
317  nh.setParam("planner/minimum_requeue_change", 1.0);
318  nh.setParam("planner/use_kernel", true);
319  nh.setParam("planner/manhattan_heuristic", false);
320  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
321 }
322 
323 
324 TEST(GlobalPlanner, AStarGridManThresh)
325 {
326  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
327  DluxGlobalPlanner planner;
328  std::string ns = "AStarGridManThresh";
329 
330  ros::NodeHandle nh("~/" + ns);
331  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
332  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
333  nh.setParam("planner/minimum_requeue_change", 1.0);
334  nh.setParam("planner/use_kernel", false);
335  nh.setParam("planner/manhattan_heuristic", true);
336  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
337 }
338 
339 
340 TEST(GlobalPlanner, AStarGridThresh)
341 {
342  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
343  DluxGlobalPlanner planner;
344  std::string ns = "AStarGridThresh";
345 
346  ros::NodeHandle nh("~/" + ns);
347  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
348  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
349  nh.setParam("planner/minimum_requeue_change", 1.0);
350  nh.setParam("planner/use_kernel", false);
351  nh.setParam("planner/manhattan_heuristic", false);
352  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
353 }
354 
355 
356 TEST(GlobalPlanner, AStarGradientStepManK)
357 {
358  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
359  DluxGlobalPlanner planner;
360  std::string ns = "AStarGradientStepManK";
361 
362  ros::NodeHandle nh("~/" + ns);
363  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
364  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
365  nh.setParam("planner/minimum_requeue_change", 0.0);
366  nh.setParam("planner/use_kernel", true);
367  nh.setParam("planner/manhattan_heuristic", true);
368  nh.setParam("planner/grid_step_near_high", true);
369  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
370 }
371 
372 
373 TEST(GlobalPlanner, AStarGradientManK)
374 {
375  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
376  DluxGlobalPlanner planner;
377  std::string ns = "AStarGradientManK";
378 
379  ros::NodeHandle nh("~/" + ns);
380  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
381  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
382  nh.setParam("planner/minimum_requeue_change", 0.0);
383  nh.setParam("planner/use_kernel", true);
384  nh.setParam("planner/manhattan_heuristic", true);
385  nh.setParam("planner/grid_step_near_high", false);
386  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
387 }
388 
389 
390 TEST(GlobalPlanner, AStarGradientStepK)
391 {
392  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
393  DluxGlobalPlanner planner;
394  std::string ns = "AStarGradientStepK";
395 
396  ros::NodeHandle nh("~/" + ns);
397  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
398  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
399  nh.setParam("planner/minimum_requeue_change", 0.0);
400  nh.setParam("planner/use_kernel", true);
401  nh.setParam("planner/manhattan_heuristic", false);
402  nh.setParam("planner/grid_step_near_high", true);
403  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
404 }
405 
406 
407 TEST(GlobalPlanner, AStarGradientK)
408 {
409  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
410  DluxGlobalPlanner planner;
411  std::string ns = "AStarGradientK";
412 
413  ros::NodeHandle nh("~/" + ns);
414  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
415  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
416  nh.setParam("planner/minimum_requeue_change", 0.0);
417  nh.setParam("planner/use_kernel", true);
418  nh.setParam("planner/manhattan_heuristic", false);
419  nh.setParam("planner/grid_step_near_high", false);
420  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
421 }
422 
423 
424 TEST(GlobalPlanner, AStarGradientStepMan)
425 {
426  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
427  DluxGlobalPlanner planner;
428  std::string ns = "AStarGradientStepMan";
429 
430  ros::NodeHandle nh("~/" + ns);
431  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
432  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
433  nh.setParam("planner/minimum_requeue_change", 0.0);
434  nh.setParam("planner/use_kernel", false);
435  nh.setParam("planner/manhattan_heuristic", true);
436  nh.setParam("planner/grid_step_near_high", true);
437  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
438 }
439 
440 
441 TEST(GlobalPlanner, AStarGradientMan)
442 {
443  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
444  DluxGlobalPlanner planner;
445  std::string ns = "AStarGradientMan";
446 
447  ros::NodeHandle nh("~/" + ns);
448  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
449  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
450  nh.setParam("planner/minimum_requeue_change", 0.0);
451  nh.setParam("planner/use_kernel", false);
452  nh.setParam("planner/manhattan_heuristic", true);
453  nh.setParam("planner/grid_step_near_high", false);
454  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
455 }
456 
457 
458 TEST(GlobalPlanner, AStarGradientStep)
459 {
460  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
461  DluxGlobalPlanner planner;
462  std::string ns = "AStarGradientStep";
463 
464  ros::NodeHandle nh("~/" + ns);
465  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
466  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
467  nh.setParam("planner/minimum_requeue_change", 0.0);
468  nh.setParam("planner/use_kernel", false);
469  nh.setParam("planner/manhattan_heuristic", false);
470  nh.setParam("planner/grid_step_near_high", true);
471  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
472 }
473 
474 
475 TEST(GlobalPlanner, AStarGradient)
476 {
477  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
478  DluxGlobalPlanner planner;
479  std::string ns = "AStarGradient";
480 
481  ros::NodeHandle nh("~/" + ns);
482  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
483  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
484  nh.setParam("planner/minimum_requeue_change", 0.0);
485  nh.setParam("planner/use_kernel", false);
486  nh.setParam("planner/manhattan_heuristic", false);
487  nh.setParam("planner/grid_step_near_high", false);
488  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
489 }
490 
491 
492 TEST(GlobalPlanner, AStarGradientStepManThreshK)
493 {
494  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
495  DluxGlobalPlanner planner;
496  std::string ns = "AStarGradientStepManThreshK";
497 
498  ros::NodeHandle nh("~/" + ns);
499  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
500  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
501  nh.setParam("planner/minimum_requeue_change", 1.0);
502  nh.setParam("planner/use_kernel", true);
503  nh.setParam("planner/manhattan_heuristic", true);
504  nh.setParam("planner/grid_step_near_high", true);
505  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
506 }
507 
508 
509 TEST(GlobalPlanner, AStarGradientManThreshK)
510 {
511  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
512  DluxGlobalPlanner planner;
513  std::string ns = "AStarGradientManThreshK";
514 
515  ros::NodeHandle nh("~/" + ns);
516  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
517  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
518  nh.setParam("planner/minimum_requeue_change", 1.0);
519  nh.setParam("planner/use_kernel", true);
520  nh.setParam("planner/manhattan_heuristic", true);
521  nh.setParam("planner/grid_step_near_high", false);
522  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
523 }
524 
525 
526 TEST(GlobalPlanner, AStarGradientStepThreshK)
527 {
528  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
529  DluxGlobalPlanner planner;
530  std::string ns = "AStarGradientStepThreshK";
531 
532  ros::NodeHandle nh("~/" + ns);
533  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
534  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
535  nh.setParam("planner/minimum_requeue_change", 1.0);
536  nh.setParam("planner/use_kernel", true);
537  nh.setParam("planner/manhattan_heuristic", false);
538  nh.setParam("planner/grid_step_near_high", true);
539  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
540 }
541 
542 
543 TEST(GlobalPlanner, AStarGradientThreshK)
544 {
545  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
546  DluxGlobalPlanner planner;
547  std::string ns = "AStarGradientThreshK";
548 
549  ros::NodeHandle nh("~/" + ns);
550  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
551  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
552  nh.setParam("planner/minimum_requeue_change", 1.0);
553  nh.setParam("planner/use_kernel", true);
554  nh.setParam("planner/manhattan_heuristic", false);
555  nh.setParam("planner/grid_step_near_high", false);
556  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
557 }
558 
559 
560 TEST(GlobalPlanner, AStarGradientStepManThresh)
561 {
562  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
563  DluxGlobalPlanner planner;
564  std::string ns = "AStarGradientStepManThresh";
565 
566  ros::NodeHandle nh("~/" + ns);
567  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
568  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
569  nh.setParam("planner/minimum_requeue_change", 1.0);
570  nh.setParam("planner/use_kernel", false);
571  nh.setParam("planner/manhattan_heuristic", true);
572  nh.setParam("planner/grid_step_near_high", true);
573  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
574 }
575 
576 
577 TEST(GlobalPlanner, AStarGradientManThresh)
578 {
579  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
580  DluxGlobalPlanner planner;
581  std::string ns = "AStarGradientManThresh";
582 
583  ros::NodeHandle nh("~/" + ns);
584  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
585  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
586  nh.setParam("planner/minimum_requeue_change", 1.0);
587  nh.setParam("planner/use_kernel", false);
588  nh.setParam("planner/manhattan_heuristic", true);
589  nh.setParam("planner/grid_step_near_high", false);
590  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
591 }
592 
593 
594 TEST(GlobalPlanner, AStarGradientStepThresh)
595 {
596  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
597  DluxGlobalPlanner planner;
598  std::string ns = "AStarGradientStepThresh";
599 
600  ros::NodeHandle nh("~/" + ns);
601  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
602  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
603  nh.setParam("planner/minimum_requeue_change", 1.0);
604  nh.setParam("planner/use_kernel", false);
605  nh.setParam("planner/manhattan_heuristic", false);
606  nh.setParam("planner/grid_step_near_high", true);
607  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
608 }
609 
610 
611 TEST(GlobalPlanner, AStarGradientThresh)
612 {
613  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
614  DluxGlobalPlanner planner;
615  std::string ns = "AStarGradientThresh";
616 
617  ros::NodeHandle nh("~/" + ns);
618  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
619  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
620  nh.setParam("planner/minimum_requeue_change", 1.0);
621  nh.setParam("planner/use_kernel", false);
622  nh.setParam("planner/manhattan_heuristic", false);
623  nh.setParam("planner/grid_step_near_high", false);
624  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
625 }
626 
627 
628 int main(int argc, char **argv)
629 {
630  ros::init(argc, argv, "planner_tests");
631  testing::InitGoogleTest(&argc, argv);
632  return RUN_ALL_TESTS();
633 }
TEST(GlobalPlanner, DijkstraVonNeumann)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
std::shared_ptr< tf::TransformListener > TFListenerPtr
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const


dlux_plugins
Author(s):
autogenerated on Sun Jan 10 2021 04:08:54