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 <string>
40 
41 using global_planner_tests::many_map_test_suite;
43 
44 
45 TEST(GlobalPlanner, DijkstraVonNeumann)
46 {
47  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
48  DluxGlobalPlanner planner;
49  std::string ns = "DijkstraVonNeumann";
50 
51  ros::NodeHandle nh("~/" + ns);
52  nh.setParam("planner/potential_calculator", "dlux_plugins::Dijkstra");
53  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
54  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
55 }
56 
57 
58 TEST(GlobalPlanner, DijkstraGrid)
59 {
60  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
61  DluxGlobalPlanner planner;
62  std::string ns = "DijkstraGrid";
63 
64  ros::NodeHandle nh("~/" + ns);
65  nh.setParam("planner/potential_calculator", "dlux_plugins::Dijkstra");
66  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
67  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
68 }
69 
70 
71 TEST(GlobalPlanner, DijkstraGradientStep)
72 {
73  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
74  DluxGlobalPlanner planner;
75  std::string ns = "DijkstraGradientStep";
76 
77  ros::NodeHandle nh("~/" + ns);
78  nh.setParam("planner/potential_calculator", "dlux_plugins::Dijkstra");
79  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
80  nh.setParam("planner/grid_step_near_high", true);
81  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
82 }
83 
84 
85 TEST(GlobalPlanner, DijkstraGradient)
86 {
87  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
88  DluxGlobalPlanner planner;
89  std::string ns = "DijkstraGradient";
90 
91  ros::NodeHandle nh("~/" + ns);
92  nh.setParam("planner/potential_calculator", "dlux_plugins::Dijkstra");
93  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
94  nh.setParam("planner/grid_step_near_high", false);
95  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
96 }
97 
98 
99 TEST(GlobalPlanner, AStarVonNeumannManK)
100 {
101  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
102  DluxGlobalPlanner planner;
103  std::string ns = "AStarVonNeumannManK";
104 
105  ros::NodeHandle nh("~/" + ns);
106  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
107  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
108  nh.setParam("planner/minimum_requeue_change", 0.0);
109  nh.setParam("planner/use_kernel", true);
110  nh.setParam("planner/manhattan_heuristic", true);
111  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
112 }
113 
114 
115 TEST(GlobalPlanner, AStarVonNeumannK)
116 {
117  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
118  DluxGlobalPlanner planner;
119  std::string ns = "AStarVonNeumannK";
120 
121  ros::NodeHandle nh("~/" + ns);
122  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
123  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
124  nh.setParam("planner/minimum_requeue_change", 0.0);
125  nh.setParam("planner/use_kernel", true);
126  nh.setParam("planner/manhattan_heuristic", false);
127  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
128 }
129 
130 
131 TEST(GlobalPlanner, AStarVonNeumannMan)
132 {
133  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
134  DluxGlobalPlanner planner;
135  std::string ns = "AStarVonNeumannMan";
136 
137  ros::NodeHandle nh("~/" + ns);
138  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
139  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
140  nh.setParam("planner/minimum_requeue_change", 0.0);
141  nh.setParam("planner/use_kernel", false);
142  nh.setParam("planner/manhattan_heuristic", true);
143  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
144 }
145 
146 
147 TEST(GlobalPlanner, AStarVonNeumann)
148 {
149  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
150  DluxGlobalPlanner planner;
151  std::string ns = "AStarVonNeumann";
152 
153  ros::NodeHandle nh("~/" + ns);
154  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
155  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
156  nh.setParam("planner/minimum_requeue_change", 0.0);
157  nh.setParam("planner/use_kernel", false);
158  nh.setParam("planner/manhattan_heuristic", false);
159  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
160 }
161 
162 
163 TEST(GlobalPlanner, AStarVonNeumannManThreshK)
164 {
165  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
166  DluxGlobalPlanner planner;
167  std::string ns = "AStarVonNeumannManThreshK";
168 
169  ros::NodeHandle nh("~/" + ns);
170  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
171  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
172  nh.setParam("planner/minimum_requeue_change", 1.0);
173  nh.setParam("planner/use_kernel", true);
174  nh.setParam("planner/manhattan_heuristic", true);
175  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
176 }
177 
178 
179 TEST(GlobalPlanner, AStarVonNeumannThreshK)
180 {
181  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
182  DluxGlobalPlanner planner;
183  std::string ns = "AStarVonNeumannThreshK";
184 
185  ros::NodeHandle nh("~/" + ns);
186  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
187  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
188  nh.setParam("planner/minimum_requeue_change", 1.0);
189  nh.setParam("planner/use_kernel", true);
190  nh.setParam("planner/manhattan_heuristic", false);
191  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
192 }
193 
194 
195 TEST(GlobalPlanner, AStarVonNeumannManThresh)
196 {
197  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
198  DluxGlobalPlanner planner;
199  std::string ns = "AStarVonNeumannManThresh";
200 
201  ros::NodeHandle nh("~/" + ns);
202  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
203  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
204  nh.setParam("planner/minimum_requeue_change", 1.0);
205  nh.setParam("planner/use_kernel", false);
206  nh.setParam("planner/manhattan_heuristic", true);
207  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
208 }
209 
210 
211 TEST(GlobalPlanner, AStarVonNeumannThresh)
212 {
213  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
214  DluxGlobalPlanner planner;
215  std::string ns = "AStarVonNeumannThresh";
216 
217  ros::NodeHandle nh("~/" + ns);
218  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
219  nh.setParam("planner/traceback", "dlux_plugins::VonNeumannPath");
220  nh.setParam("planner/minimum_requeue_change", 1.0);
221  nh.setParam("planner/use_kernel", false);
222  nh.setParam("planner/manhattan_heuristic", false);
223  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
224 }
225 
226 
227 TEST(GlobalPlanner, AStarGridManK)
228 {
229  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
230  DluxGlobalPlanner planner;
231  std::string ns = "AStarGridManK";
232 
233  ros::NodeHandle nh("~/" + ns);
234  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
235  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
236  nh.setParam("planner/minimum_requeue_change", 0.0);
237  nh.setParam("planner/use_kernel", true);
238  nh.setParam("planner/manhattan_heuristic", true);
239  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
240 }
241 
242 
243 TEST(GlobalPlanner, AStarGridK)
244 {
245  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
246  DluxGlobalPlanner planner;
247  std::string ns = "AStarGridK";
248 
249  ros::NodeHandle nh("~/" + ns);
250  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
251  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
252  nh.setParam("planner/minimum_requeue_change", 0.0);
253  nh.setParam("planner/use_kernel", true);
254  nh.setParam("planner/manhattan_heuristic", false);
255  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
256 }
257 
258 
259 TEST(GlobalPlanner, AStarGridMan)
260 {
261  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
262  DluxGlobalPlanner planner;
263  std::string ns = "AStarGridMan";
264 
265  ros::NodeHandle nh("~/" + ns);
266  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
267  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
268  nh.setParam("planner/minimum_requeue_change", 0.0);
269  nh.setParam("planner/use_kernel", false);
270  nh.setParam("planner/manhattan_heuristic", true);
271  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
272 }
273 
274 
275 TEST(GlobalPlanner, AStarGrid)
276 {
277  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
278  DluxGlobalPlanner planner;
279  std::string ns = "AStarGrid";
280 
281  ros::NodeHandle nh("~/" + ns);
282  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
283  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
284  nh.setParam("planner/minimum_requeue_change", 0.0);
285  nh.setParam("planner/use_kernel", false);
286  nh.setParam("planner/manhattan_heuristic", false);
287  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
288 }
289 
290 
291 TEST(GlobalPlanner, AStarGridManThreshK)
292 {
293  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
294  DluxGlobalPlanner planner;
295  std::string ns = "AStarGridManThreshK";
296 
297  ros::NodeHandle nh("~/" + ns);
298  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
299  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
300  nh.setParam("planner/minimum_requeue_change", 1.0);
301  nh.setParam("planner/use_kernel", true);
302  nh.setParam("planner/manhattan_heuristic", true);
303  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
304 }
305 
306 
307 TEST(GlobalPlanner, AStarGridThreshK)
308 {
309  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
310  DluxGlobalPlanner planner;
311  std::string ns = "AStarGridThreshK";
312 
313  ros::NodeHandle nh("~/" + ns);
314  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
315  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
316  nh.setParam("planner/minimum_requeue_change", 1.0);
317  nh.setParam("planner/use_kernel", true);
318  nh.setParam("planner/manhattan_heuristic", false);
319  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
320 }
321 
322 
323 TEST(GlobalPlanner, AStarGridManThresh)
324 {
325  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
326  DluxGlobalPlanner planner;
327  std::string ns = "AStarGridManThresh";
328 
329  ros::NodeHandle nh("~/" + ns);
330  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
331  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
332  nh.setParam("planner/minimum_requeue_change", 1.0);
333  nh.setParam("planner/use_kernel", false);
334  nh.setParam("planner/manhattan_heuristic", true);
335  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
336 }
337 
338 
339 TEST(GlobalPlanner, AStarGridThresh)
340 {
341  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
342  DluxGlobalPlanner planner;
343  std::string ns = "AStarGridThresh";
344 
345  ros::NodeHandle nh("~/" + ns);
346  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
347  nh.setParam("planner/traceback", "dlux_plugins::GridPath");
348  nh.setParam("planner/minimum_requeue_change", 1.0);
349  nh.setParam("planner/use_kernel", false);
350  nh.setParam("planner/manhattan_heuristic", false);
351  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
352 }
353 
354 
355 TEST(GlobalPlanner, AStarGradientStepManK)
356 {
357  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
358  DluxGlobalPlanner planner;
359  std::string ns = "AStarGradientStepManK";
360 
361  ros::NodeHandle nh("~/" + ns);
362  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
363  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
364  nh.setParam("planner/minimum_requeue_change", 0.0);
365  nh.setParam("planner/use_kernel", true);
366  nh.setParam("planner/manhattan_heuristic", true);
367  nh.setParam("planner/grid_step_near_high", true);
368  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
369 }
370 
371 
372 TEST(GlobalPlanner, AStarGradientManK)
373 {
374  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
375  DluxGlobalPlanner planner;
376  std::string ns = "AStarGradientManK";
377 
378  ros::NodeHandle nh("~/" + ns);
379  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
380  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
381  nh.setParam("planner/minimum_requeue_change", 0.0);
382  nh.setParam("planner/use_kernel", true);
383  nh.setParam("planner/manhattan_heuristic", true);
384  nh.setParam("planner/grid_step_near_high", false);
385  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
386 }
387 
388 
389 TEST(GlobalPlanner, AStarGradientStepK)
390 {
391  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
392  DluxGlobalPlanner planner;
393  std::string ns = "AStarGradientStepK";
394 
395  ros::NodeHandle nh("~/" + ns);
396  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
397  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
398  nh.setParam("planner/minimum_requeue_change", 0.0);
399  nh.setParam("planner/use_kernel", true);
400  nh.setParam("planner/manhattan_heuristic", false);
401  nh.setParam("planner/grid_step_near_high", true);
402  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
403 }
404 
405 
406 TEST(GlobalPlanner, AStarGradientK)
407 {
408  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
409  DluxGlobalPlanner planner;
410  std::string ns = "AStarGradientK";
411 
412  ros::NodeHandle nh("~/" + ns);
413  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
414  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
415  nh.setParam("planner/minimum_requeue_change", 0.0);
416  nh.setParam("planner/use_kernel", true);
417  nh.setParam("planner/manhattan_heuristic", false);
418  nh.setParam("planner/grid_step_near_high", false);
419  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
420 }
421 
422 
423 TEST(GlobalPlanner, AStarGradientStepMan)
424 {
425  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
426  DluxGlobalPlanner planner;
427  std::string ns = "AStarGradientStepMan";
428 
429  ros::NodeHandle nh("~/" + ns);
430  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
431  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
432  nh.setParam("planner/minimum_requeue_change", 0.0);
433  nh.setParam("planner/use_kernel", false);
434  nh.setParam("planner/manhattan_heuristic", true);
435  nh.setParam("planner/grid_step_near_high", true);
436  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
437 }
438 
439 
440 TEST(GlobalPlanner, AStarGradientMan)
441 {
442  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
443  DluxGlobalPlanner planner;
444  std::string ns = "AStarGradientMan";
445 
446  ros::NodeHandle nh("~/" + ns);
447  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
448  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
449  nh.setParam("planner/minimum_requeue_change", 0.0);
450  nh.setParam("planner/use_kernel", false);
451  nh.setParam("planner/manhattan_heuristic", true);
452  nh.setParam("planner/grid_step_near_high", false);
453  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
454 }
455 
456 
457 TEST(GlobalPlanner, AStarGradientStep)
458 {
459  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
460  DluxGlobalPlanner planner;
461  std::string ns = "AStarGradientStep";
462 
463  ros::NodeHandle nh("~/" + ns);
464  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
465  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
466  nh.setParam("planner/minimum_requeue_change", 0.0);
467  nh.setParam("planner/use_kernel", false);
468  nh.setParam("planner/manhattan_heuristic", false);
469  nh.setParam("planner/grid_step_near_high", true);
470  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
471 }
472 
473 
474 TEST(GlobalPlanner, AStarGradient)
475 {
476  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
477  DluxGlobalPlanner planner;
478  std::string ns = "AStarGradient";
479 
480  ros::NodeHandle nh("~/" + ns);
481  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
482  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
483  nh.setParam("planner/minimum_requeue_change", 0.0);
484  nh.setParam("planner/use_kernel", false);
485  nh.setParam("planner/manhattan_heuristic", false);
486  nh.setParam("planner/grid_step_near_high", false);
487  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
488 }
489 
490 
491 TEST(GlobalPlanner, AStarGradientStepManThreshK)
492 {
493  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
494  DluxGlobalPlanner planner;
495  std::string ns = "AStarGradientStepManThreshK";
496 
497  ros::NodeHandle nh("~/" + ns);
498  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
499  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
500  nh.setParam("planner/minimum_requeue_change", 1.0);
501  nh.setParam("planner/use_kernel", true);
502  nh.setParam("planner/manhattan_heuristic", true);
503  nh.setParam("planner/grid_step_near_high", true);
504  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
505 }
506 
507 
508 TEST(GlobalPlanner, AStarGradientManThreshK)
509 {
510  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
511  DluxGlobalPlanner planner;
512  std::string ns = "AStarGradientManThreshK";
513 
514  ros::NodeHandle nh("~/" + ns);
515  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
516  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
517  nh.setParam("planner/minimum_requeue_change", 1.0);
518  nh.setParam("planner/use_kernel", true);
519  nh.setParam("planner/manhattan_heuristic", true);
520  nh.setParam("planner/grid_step_near_high", false);
521  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
522 }
523 
524 
525 TEST(GlobalPlanner, AStarGradientStepThreshK)
526 {
527  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
528  DluxGlobalPlanner planner;
529  std::string ns = "AStarGradientStepThreshK";
530 
531  ros::NodeHandle nh("~/" + ns);
532  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
533  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
534  nh.setParam("planner/minimum_requeue_change", 1.0);
535  nh.setParam("planner/use_kernel", true);
536  nh.setParam("planner/manhattan_heuristic", false);
537  nh.setParam("planner/grid_step_near_high", true);
538  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
539 }
540 
541 
542 TEST(GlobalPlanner, AStarGradientThreshK)
543 {
544  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
545  DluxGlobalPlanner planner;
546  std::string ns = "AStarGradientThreshK";
547 
548  ros::NodeHandle nh("~/" + ns);
549  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
550  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
551  nh.setParam("planner/minimum_requeue_change", 1.0);
552  nh.setParam("planner/use_kernel", true);
553  nh.setParam("planner/manhattan_heuristic", false);
554  nh.setParam("planner/grid_step_near_high", false);
555  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
556 }
557 
558 
559 TEST(GlobalPlanner, AStarGradientStepManThresh)
560 {
561  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
562  DluxGlobalPlanner planner;
563  std::string ns = "AStarGradientStepManThresh";
564 
565  ros::NodeHandle nh("~/" + ns);
566  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
567  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
568  nh.setParam("planner/minimum_requeue_change", 1.0);
569  nh.setParam("planner/use_kernel", false);
570  nh.setParam("planner/manhattan_heuristic", true);
571  nh.setParam("planner/grid_step_near_high", true);
572  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
573 }
574 
575 
576 TEST(GlobalPlanner, AStarGradientManThresh)
577 {
578  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
579  DluxGlobalPlanner planner;
580  std::string ns = "AStarGradientManThresh";
581 
582  ros::NodeHandle nh("~/" + ns);
583  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
584  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
585  nh.setParam("planner/minimum_requeue_change", 1.0);
586  nh.setParam("planner/use_kernel", false);
587  nh.setParam("planner/manhattan_heuristic", true);
588  nh.setParam("planner/grid_step_near_high", false);
589  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
590 }
591 
592 
593 TEST(GlobalPlanner, AStarGradientStepThresh)
594 {
595  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
596  DluxGlobalPlanner planner;
597  std::string ns = "AStarGradientStepThresh";
598 
599  ros::NodeHandle nh("~/" + ns);
600  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
601  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
602  nh.setParam("planner/minimum_requeue_change", 1.0);
603  nh.setParam("planner/use_kernel", false);
604  nh.setParam("planner/manhattan_heuristic", false);
605  nh.setParam("planner/grid_step_near_high", true);
606  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
607 }
608 
609 
610 TEST(GlobalPlanner, AStarGradientThresh)
611 {
612  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
613  DluxGlobalPlanner planner;
614  std::string ns = "AStarGradientThresh";
615 
616  ros::NodeHandle nh("~/" + ns);
617  nh.setParam("planner/potential_calculator", "dlux_plugins::AStar");
618  nh.setParam("planner/traceback", "dlux_plugins::GradientPath");
619  nh.setParam("planner/minimum_requeue_change", 1.0);
620  nh.setParam("planner/use_kernel", false);
621  nh.setParam("planner/manhattan_heuristic", false);
622  nh.setParam("planner/grid_step_near_high", false);
623  EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
624 }
625 
626 
627 int main(int argc, char **argv)
628 {
629  ros::init(argc, argv, "planner_tests");
630  testing::InitGoogleTest(&argc, argv);
631  return RUN_ALL_TESTS();
632 }
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 Wed Jun 26 2019 20:06:32