timing_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Copyright (c) 2017 Robert Bosch GmbH.
3 * All rights reserved.
4 *
5 * Licensed under the Apache License, Version 2.0 (the "License");
6 * you may not use this file except in compliance with the License.
7 * You may obtain a copy of the License at
8 *
9 * http://www.apache.org/licenses/LICENSE-2.0
10 *
11 * Unless required by applicable law or agreed to in writing, software
12 * distributed under the License is distributed on an "AS IS" BASIS,
13 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 * See the License for the specific language governing permissions and
15 * limitations under the License.
16 * *********************************************************************/
17 
18 #include <gtest/gtest.h>
19 #include <time.h>
20 #include <fstream>
21 #include <iostream>
22 
23 #include <ros/package.h>
24 
39 
40 #define EPS_KAPPA 1e-3 // [1/m]
41 #define KAPPA 1.0 // [1/m]
42 #define SIGMA 1.0 // [1/m^2]
43 #define DISCRETIZATION 0.1 // [m]
44 #define SAMPLES 1e5 // [-]
45 #define OPERATING_REGION_X 20.0 // [m]
46 #define OPERATING_REGION_Y 20.0 // [m]
47 #define OPERATING_REGION_THETA 2 * M_PI // [rad]
48 #define ALPHA1 0.1 // [-]
49 #define ALPHA2 0.05 // [-]
50 #define ALPHA3 0.05 // [-]
51 #define ALPHA4 0.1 // [-]
52 #define STD_X 0.1 // [m]
53 #define STD_Y 0.1 // [m]
54 #define STD_THETA 0.05 // [rad]
55 #define K1 1.5 // [-]
56 #define K2 0.25 // [-]
57 #define K3 1.0 // [-]
58 #define random(lower, upper) (rand() * (upper - lower) / RAND_MAX + lower)
59 
60 using namespace std;
61 using namespace steering;
62 
63 struct Statistic
64 {
68  double path_length;
70 };
71 
73 {
74  State state;
75  state.x = random(-OPERATING_REGION_X / 2.0, OPERATING_REGION_X / 2.0);
76  state.y = random(-OPERATING_REGION_Y / 2.0, OPERATING_REGION_Y / 2.0);
78  state.kappa = random(-KAPPA, KAPPA);
79  state.d = 0.0;
80  return state;
81 }
82 
83 double get_mean(const vector<double>& v)
84 {
85  double sum = accumulate(v.begin(), v.end(), 0.0);
86  return sum / v.size();
87 }
88 
89 double get_std(const vector<double>& v)
90 {
91  double mean = get_mean(v);
92  double diff_sq = 0;
93  for (const auto& x : v)
94  {
95  diff_sq += pow(x - mean, 2);
96  }
97  return sqrt(diff_sq / v.size());
98 }
99 
100 int get_curv_discont(const vector<Control>& controls)
101 {
102  int curv_discont = 0;
103  vector<Control>::const_iterator iter1 = controls.begin();
104  for (vector<Control>::const_iterator iter2 = next(controls.begin()); iter2 != controls.end(); ++iter2)
105  {
106  if (fabs(iter1->kappa + iter1->sigma * fabs(iter1->delta_s) - iter2->kappa) > EPS_KAPPA)
107  ++curv_discont;
108  iter1 = iter2;
109  }
110  return curv_discont;
111 }
112 
113 void write_to_file(const string& id, const vector<Statistic>& stats)
114 {
115  string path_to_output = ros::package::getPath("steering_functions") + "/test/" + id + "_stats.csv";
116  remove(path_to_output.c_str());
117  string header = "start,goal,computation_time,path_length";
118  fstream f;
119  f.open(path_to_output, ios::app);
120  f << header << endl;
121  for (const auto& stat : stats)
122  {
123  State start = stat.start;
124  State goal = stat.goal;
125  f << start.x << " " << start.y << " " << start.theta << " " << start.kappa << " " << start.d << ",";
126  f << goal.x << " " << goal.y << " " << goal.theta << " " << goal.kappa << " " << goal.d << ",";
127  f << stat.computation_time << "," << stat.path_length << "," << stat.curv_discont << endl;
128  }
129 }
130 
145 
146 vector<Statistic> get_controls(const string& id, const vector<State>& starts, const vector<State>& goals)
147 {
148  clock_t clock_start;
149  clock_t clock_finish;
150  Statistic stat;
151  vector<Statistic> stats;
152  stats.reserve(SAMPLES);
153  double path_length;
154  int curv_discont;
155  for (auto start = starts.begin(), goal = goals.begin(); start != starts.end(); ++start, ++goal)
156  {
157  if (id == "CC_Dubins")
158  {
159  clock_start = clock();
160  vector<Control> cc_dubins_forwards_controls = cc_dubins_forwards_ss.get_controls(*start, *goal);
161  clock_finish = clock();
162  path_length = cc_dubins_forwards_ss.get_distance(*start, *goal);
163  curv_discont = get_curv_discont(cc_dubins_forwards_controls);
164  }
165  else if (id == "CC00_Dubins")
166  {
167  clock_start = clock();
168  vector<Control> cc00_dubins_forwards_controls = cc00_dubins_forwards_ss.get_controls(*start, *goal);
169  clock_finish = clock();
170  path_length = cc00_dubins_forwards_ss.get_distance(*start, *goal);
171  curv_discont = get_curv_discont(cc00_dubins_forwards_controls);
172  }
173  else if (id == "CC0pm_Dubins")
174  {
175  clock_start = clock();
176  vector<Control> cc0pm_dubins_forwards_controls = cc0pm_dubins_forwards_ss.get_controls(*start, *goal);
177  clock_finish = clock();
178  path_length = cc0pm_dubins_forwards_ss.get_distance(*start, *goal);
179  curv_discont = get_curv_discont(cc0pm_dubins_forwards_controls);
180  }
181  else if (id == "CCpm0_Dubins")
182  {
183  clock_start = clock();
184  vector<Control> ccpm0_dubins_forwards_controls = ccpm0_dubins_forwards_ss.get_controls(*start, *goal);
185  clock_finish = clock();
186  path_length = ccpm0_dubins_forwards_ss.get_distance(*start, *goal);
187  curv_discont = get_curv_discont(ccpm0_dubins_forwards_controls);
188  }
189  else if (id == "CCpmpm_Dubins")
190  {
191  clock_start = clock();
192  vector<Control> ccpmpm_dubins_forwards_controls = ccpmpm_dubins_forwards_ss.get_controls(*start, *goal);
193  clock_finish = clock();
194  path_length = ccpmpm_dubins_forwards_ss.get_distance(*start, *goal);
195  curv_discont = get_curv_discont(ccpmpm_dubins_forwards_controls);
196  }
197  else if (id == "Dubins")
198  {
199  clock_start = clock();
200  vector<Control> dubins_forwards_controls = dubins_forwards_ss.get_controls(*start, *goal);
201  clock_finish = clock();
202  path_length = dubins_forwards_ss.get_distance(*start, *goal);
203  curv_discont = get_curv_discont(dubins_forwards_controls);
204  }
205  else if (id == "CC00_RS")
206  {
207  clock_start = clock();
208  vector<Control> cc00_rs_controls = cc00_rs_ss.get_controls(*start, *goal);
209  clock_finish = clock();
210  path_length = cc00_rs_ss.get_distance(*start, *goal);
211  curv_discont = get_curv_discont(cc00_rs_controls);
212  }
213  else if (id == "HC_RS")
214  {
215  clock_start = clock();
216  vector<Control> hc_rs_controls = hc_rs_ss.get_controls(*start, *goal);
217  clock_finish = clock();
218  path_length = hc_rs_ss.get_distance(*start, *goal);
219  curv_discont = get_curv_discont(hc_rs_controls);
220  }
221  else if (id == "HC00_RS")
222  {
223  clock_start = clock();
224  vector<Control> hc00_rs_controls = hc00_rs_ss.get_controls(*start, *goal);
225  clock_finish = clock();
226  path_length = hc00_rs_ss.get_distance(*start, *goal);
227  curv_discont = get_curv_discont(hc00_rs_controls);
228  }
229  else if (id == "HC0pm_RS")
230  {
231  clock_start = clock();
232  vector<Control> hc0pm_rs_controls = hc0pm_rs_ss.get_controls(*start, *goal);
233  clock_finish = clock();
234  path_length = hc0pm_rs_ss.get_distance(*start, *goal);
235  curv_discont = get_curv_discont(hc0pm_rs_controls);
236  }
237  else if (id == "HCpm0_RS")
238  {
239  clock_start = clock();
240  vector<Control> hcpm0_rs_controls = hcpm0_rs_ss.get_controls(*start, *goal);
241  clock_finish = clock();
242  path_length = hcpm0_rs_ss.get_distance(*start, *goal);
243  curv_discont = get_curv_discont(hcpm0_rs_controls);
244  }
245  else if (id == "HCpmpm_RS")
246  {
247  clock_start = clock();
248  vector<Control> hcpmpm_rs_controls = hcpmpm_rs_ss.get_controls(*start, *goal);
249  clock_finish = clock();
250  path_length = hcpmpm_rs_ss.get_distance(*start, *goal);
251  curv_discont = get_curv_discont(hcpmpm_rs_controls);
252  }
253  else if (id == "RS")
254  {
255  clock_start = clock();
256  vector<Control> rs_controls = rs_ss.get_controls(*start, *goal);
257  clock_finish = clock();
258  path_length = rs_ss.get_distance(*start, *goal);
259  curv_discont = get_curv_discont(rs_controls);
260  }
261  stat.start = *start;
262  stat.goal = *goal;
263  stat.computation_time = double(clock_finish - clock_start) / CLOCKS_PER_SEC;
264  stat.path_length = path_length;
265  stat.curv_discont = curv_discont;
266  stats.push_back(stat);
267  }
268  return stats;
269 }
270 
271 vector<Statistic> get_path(const string& id, const vector<State>& starts, const vector<State>& goals)
272 {
273  clock_t clock_start;
274  clock_t clock_finish;
275  Statistic stat;
276  vector<Statistic> stats;
277  stats.reserve(SAMPLES);
278  for (auto start = starts.begin(), goal = goals.begin(); start != starts.end(); ++start, ++goal)
279  {
280  if (id == "CC_Dubins")
281  {
282  clock_start = clock();
284  clock_finish = clock();
285  }
286  else if (id == "CC00_Dubins")
287  {
288  clock_start = clock();
290  clock_finish = clock();
291  }
292  else if (id == "CC0pm_Dubins")
293  {
294  clock_start = clock();
296  clock_finish = clock();
297  }
298  else if (id == "CCpm0_Dubins")
299  {
300  clock_start = clock();
302  clock_finish = clock();
303  }
304  else if (id == "CCpmpm_Dubins")
305  {
306  clock_start = clock();
308  clock_finish = clock();
309  }
310  else if (id == "Dubins")
311  {
312  clock_start = clock();
314  clock_finish = clock();
315  }
316  else if (id == "CC00_RS")
317  {
318  clock_start = clock();
319  cc00_rs_ss.get_path(*start, *goal);
320  clock_finish = clock();
321  }
322  else if (id == "HC_RS")
323  {
324  clock_start = clock();
325  hc_rs_ss.get_path(*start, *goal);
326  clock_finish = clock();
327  }
328  else if (id == "HC00_RS")
329  {
330  clock_start = clock();
331  hc00_rs_ss.get_path(*start, *goal);
332  clock_finish = clock();
333  }
334  else if (id == "HC0pm_RS")
335  {
336  clock_start = clock();
337  hc0pm_rs_ss.get_path(*start, *goal);
338  clock_finish = clock();
339  }
340  else if (id == "HCpm0_RS")
341  {
342  clock_start = clock();
343  hcpm0_rs_ss.get_path(*start, *goal);
344  clock_finish = clock();
345  }
346  else if (id == "HCpmpm_RS")
347  {
348  clock_start = clock();
349  hcpmpm_rs_ss.get_path(*start, *goal);
350  clock_finish = clock();
351  }
352  else if (id == "RS")
353  {
354  clock_start = clock();
355  rs_ss.get_path(*start, *goal);
356  clock_finish = clock();
357  }
358  stat.start = *start;
359  stat.goal = *goal;
360  stat.computation_time = double(clock_finish - clock_start) / CLOCKS_PER_SEC;
361  stats.push_back(stat);
362  }
363  return stats;
364 }
365 
366 vector<Statistic> get_path_with_covariance(const string& id, const vector<State_With_Covariance>& starts,
367  const vector<State>& goals)
368 {
369  clock_t clock_start;
370  clock_t clock_finish;
371  Statistic stat;
372  vector<Statistic> stats;
373  stats.reserve(SAMPLES);
374  auto start = starts.begin();
375  auto goal = goals.begin();
376  for (start = starts.begin(), goal = goals.begin(); start != starts.end(); ++start, ++goal)
377  {
378  if (id == "CC_Dubins")
379  {
380  clock_start = clock();
382  clock_finish = clock();
383  }
384  else if (id == "CC00_Dubins")
385  {
386  clock_start = clock();
388  clock_finish = clock();
389  }
390  if (id == "CC0pm_Dubins")
391  {
392  clock_start = clock();
394  clock_finish = clock();
395  }
396  if (id == "CCpm0_Dubins")
397  {
398  clock_start = clock();
400  clock_finish = clock();
401  }
402  if (id == "CCpmpm_Dubins")
403  {
404  clock_start = clock();
406  clock_finish = clock();
407  }
408  else if (id == "Dubins")
409  {
410  clock_start = clock();
412  clock_finish = clock();
413  }
414  else if (id == "CC00_RS")
415  {
416  clock_start = clock();
418  clock_finish = clock();
419  }
420  else if (id == "HC_RS")
421  {
422  clock_start = clock();
424  clock_finish = clock();
425  }
426  else if (id == "HC00_RS")
427  {
428  clock_start = clock();
430  clock_finish = clock();
431  }
432  else if (id == "HC0pm_RS")
433  {
434  clock_start = clock();
436  clock_finish = clock();
437  }
438  else if (id == "HCpm0_RS")
439  {
440  clock_start = clock();
442  clock_finish = clock();
443  }
444  else if (id == "HCpmpm_RS")
445  {
446  clock_start = clock();
448  clock_finish = clock();
449  }
450  else if (id == "RS")
451  {
452  clock_start = clock();
454  clock_finish = clock();
455  }
456  stat.start = start->state;
457  stat.goal = *goal;
458  stat.computation_time = double(clock_finish - clock_start) / CLOCKS_PER_SEC;
459  stats.push_back(stat);
460  }
461  return stats;
462 }
463 
464 TEST(Timing, getControls)
465 {
466  srand(0);
467  vector<double> computation_times;
468  computation_times.reserve(SAMPLES);
469  vector<State> starts_with_curvature, starts_without_curvature;
470  starts_with_curvature.reserve(SAMPLES);
471  starts_without_curvature.reserve(SAMPLES);
472  vector<State> goals_with_curvature, goals_without_curvature;
473  goals_with_curvature.reserve(SAMPLES);
474  goals_without_curvature.reserve(SAMPLES);
475  for (int i = 0; i < SAMPLES; i++)
476  {
478  State goal = get_random_state();
479  starts_with_curvature.push_back(start);
480  goals_with_curvature.push_back(goal);
481  start.kappa = 0.0;
482  goal.kappa = 0.0;
483  starts_without_curvature.push_back(start);
484  goals_without_curvature.push_back(goal);
485  }
486 
487  string cc_dubins_id = "CC_Dubins";
488  vector<Statistic> cc_dubins_stats = get_controls(cc_dubins_id, starts_with_curvature, goals_with_curvature);
489  computation_times.clear();
490  for (const auto& stat : cc_dubins_stats)
491  {
492  computation_times.push_back(stat.computation_time);
493  }
494  cout << "[----------] " + cc_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
495  << get_std(computation_times) << endl;
496 
497  string cc00_dubins_id = "CC00_Dubins";
498  vector<Statistic> cc00_dubins_stats = get_controls(cc00_dubins_id, starts_without_curvature, goals_without_curvature);
499  computation_times.clear();
500  for (const auto& stat : cc00_dubins_stats)
501  {
502  computation_times.push_back(stat.computation_time);
503  }
504  cout << "[----------] " + cc00_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
505  << get_std(computation_times) << endl;
506 
507  string cc0pm_dubins_id = "CC0pm_Dubins";
508  vector<Statistic> cc0pm_dubins_stats =
509  get_controls(cc0pm_dubins_id, starts_without_curvature, goals_without_curvature);
510  computation_times.clear();
511  for (const auto& stat : cc0pm_dubins_stats)
512  {
513  computation_times.push_back(stat.computation_time);
514  }
515  cout << "[----------] " + cc0pm_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
516  << get_std(computation_times) << endl;
517 
518  string ccpm0_dubins_id = "CCpm0_Dubins";
519  vector<Statistic> ccpm0_dubins_stats =
520  get_controls(ccpm0_dubins_id, starts_without_curvature, goals_without_curvature);
521  computation_times.clear();
522  for (const auto& stat : ccpm0_dubins_stats)
523  {
524  computation_times.push_back(stat.computation_time);
525  }
526  cout << "[----------] " + ccpm0_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
527  << get_std(computation_times) << endl;
528 
529  string ccpmpm_dubins_id = "CCpmpm_Dubins";
530  vector<Statistic> ccpmpm_dubins_stats =
531  get_controls(ccpmpm_dubins_id, starts_without_curvature, goals_without_curvature);
532  computation_times.clear();
533  for (const auto& stat : ccpmpm_dubins_stats)
534  {
535  computation_times.push_back(stat.computation_time);
536  }
537  cout << "[----------] " + ccpmpm_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
538  << get_std(computation_times) << endl;
539 
540  string dubins_id = "Dubins";
541  vector<Statistic> dubins_stats = get_controls(dubins_id, starts_without_curvature, goals_without_curvature);
542  computation_times.clear();
543  for (const auto& stat : dubins_stats)
544  {
545  computation_times.push_back(stat.computation_time);
546  }
547  cout << "[----------] " + dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
548  << get_std(computation_times) << endl;
549 
550  string cc00_rs_id = "CC00_RS";
551  vector<Statistic> cc00_rs_stats = get_controls(cc00_rs_id, starts_without_curvature, goals_without_curvature);
552  computation_times.clear();
553  for (const auto& stat : cc00_rs_stats)
554  {
555  computation_times.push_back(stat.computation_time);
556  }
557  cout << "[----------] " + cc00_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
558  << get_std(computation_times) << endl;
559 
560  string hc_rs_id = "HC_RS";
561  vector<Statistic> hc_rs_stats = get_controls(hc_rs_id, starts_with_curvature, goals_with_curvature);
562  computation_times.clear();
563  for (const auto& stat : hc_rs_stats)
564  {
565  computation_times.push_back(stat.computation_time);
566  }
567  cout << "[----------] " + hc_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
568  << get_std(computation_times) << endl;
569 
570  string hc00_rs_id = "HC00_RS";
571  vector<Statistic> hc00_rs_stats = get_controls(hc00_rs_id, starts_without_curvature, goals_without_curvature);
572  computation_times.clear();
573  for (const auto& stat : hc00_rs_stats)
574  {
575  computation_times.push_back(stat.computation_time);
576  }
577  cout << "[----------] " + hc00_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
578  << get_std(computation_times) << endl;
579 
580  string hc0pm_rs_id = "HC0pm_RS";
581  vector<Statistic> hc0pm_rs_stats = get_controls(hc0pm_rs_id, starts_without_curvature, goals_without_curvature);
582  computation_times.clear();
583  for (const auto& stat : hc0pm_rs_stats)
584  {
585  computation_times.push_back(stat.computation_time);
586  }
587  cout << "[----------] " + hc0pm_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
588  << get_std(computation_times) << endl;
589 
590  string hcpm0_rs_id = "HCpm0_RS";
591  vector<Statistic> hcpm0_rs_stats = get_controls(hcpm0_rs_id, starts_without_curvature, goals_without_curvature);
592  computation_times.clear();
593  for (const auto& stat : hcpm0_rs_stats)
594  {
595  computation_times.push_back(stat.computation_time);
596  }
597  cout << "[----------] " + hcpm0_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
598  << get_std(computation_times) << endl;
599 
600  string hcpmpm_rs_id = "HCpmpm_RS";
601  vector<Statistic> hcpmpm_rs_stats = get_controls(hcpmpm_rs_id, starts_without_curvature, goals_without_curvature);
602  computation_times.clear();
603  for (const auto& stat : hcpmpm_rs_stats)
604  {
605  computation_times.push_back(stat.computation_time);
606  }
607  cout << "[----------] " + hcpmpm_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
608  << get_std(computation_times) << endl;
609 
610  string rs_id = "RS";
611  vector<Statistic> rs_stats = get_controls(rs_id, starts_without_curvature, goals_without_curvature);
612  computation_times.clear();
613  for (const auto& stat : rs_stats)
614  {
615  computation_times.push_back(stat.computation_time);
616  }
617  cout << "[----------] " + rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
618  << get_std(computation_times) << endl;
619 
620  // write_to_file(cc_dubins_id, cc_dubins_stats);
621  // write_to_file(cc00_dubins_id, cc00_dubins_stats);
622  // write_to_file(cc0pm_dubins_id, cc0pm_dubins_stats);
623  // write_to_file(ccpm0_dubins_id, ccpm0_dubins_stats);
624  // write_to_file(ccpmpm_dubins_id, ccpmpm_dubins_stats);
625  // write_to_file(dubins_id, dubins_stats);
626  // write_to_file(cc00_rs_id, cc00_rs_stats);
627  // write_to_file(hc_rs_id, hc_rs_stats);
628  // write_to_file(hc00_rs_id, hc00_rs_stats);
629  // write_to_file(hc0pm_rs_id, hc0pm_rs_stats);
630  // write_to_file(hcpm0_rs_id, hcpm0_rs_stats);
631  // write_to_file(hcpmpm_rs_id, hcpmpm_rs_stats);
632  // write_to_file(rs_id, rs_stats);
633 }
634 
635 TEST(Timing, getPath)
636 {
637  srand(0);
638  vector<double> computation_times;
639  computation_times.reserve(SAMPLES);
640  vector<State> starts_with_curvature, starts_without_curvature;
641  starts_with_curvature.reserve(SAMPLES);
642  starts_without_curvature.reserve(SAMPLES);
643  vector<State> goals_with_curvature, goals_without_curvature;
644  goals_with_curvature.reserve(SAMPLES);
645  goals_without_curvature.reserve(SAMPLES);
646  for (int i = 0; i < SAMPLES; i++)
647  {
649  State goal = get_random_state();
650  starts_with_curvature.push_back(start);
651  goals_with_curvature.push_back(goal);
652  start.kappa = 0.0;
653  goal.kappa = 0.0;
654  starts_without_curvature.push_back(start);
655  goals_without_curvature.push_back(goal);
656  }
657 
658  string cc_dubins_id = "CC_Dubins";
659  vector<Statistic> cc_dubins_stats = get_path(cc_dubins_id, starts_with_curvature, goals_with_curvature);
660  computation_times.clear();
661  for (const auto& stat : cc_dubins_stats)
662  {
663  computation_times.push_back(stat.computation_time);
664  }
665  cout << "[----------] " + cc_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
666  << get_std(computation_times) << endl;
667 
668  string cc00_dubins_id = "CC00_Dubins";
669  vector<Statistic> cc00_dubins_stats = get_path(cc00_dubins_id, starts_without_curvature, goals_without_curvature);
670  computation_times.clear();
671  for (const auto& stat : cc00_dubins_stats)
672  {
673  computation_times.push_back(stat.computation_time);
674  }
675  cout << "[----------] " + cc00_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
676  << get_std(computation_times) << endl;
677 
678  string cc0pm_dubins_id = "CC0pm_Dubins";
679  vector<Statistic> cc0pm_dubins_stats = get_path(cc0pm_dubins_id, starts_without_curvature, goals_without_curvature);
680  computation_times.clear();
681  for (const auto& stat : cc0pm_dubins_stats)
682  {
683  computation_times.push_back(stat.computation_time);
684  }
685  cout << "[----------] " + cc0pm_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
686  << get_std(computation_times) << endl;
687 
688  string ccpm0_dubins_id = "CCpm0_Dubins";
689  vector<Statistic> ccpm0_dubins_stats = get_path(ccpm0_dubins_id, starts_without_curvature, goals_without_curvature);
690  computation_times.clear();
691  for (const auto& stat : ccpm0_dubins_stats)
692  {
693  computation_times.push_back(stat.computation_time);
694  }
695  cout << "[----------] " + ccpm0_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
696  << get_std(computation_times) << endl;
697 
698  string ccpmpm_dubins_id = "CCpmpm_Dubins";
699  vector<Statistic> ccpmpm_dubins_stats = get_path(ccpmpm_dubins_id, starts_without_curvature, goals_without_curvature);
700  computation_times.clear();
701  for (const auto& stat : ccpmpm_dubins_stats)
702  {
703  computation_times.push_back(stat.computation_time);
704  }
705  cout << "[----------] " + ccpmpm_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
706  << get_std(computation_times) << endl;
707 
708  string dubins_id = "Dubins";
709  vector<Statistic> dubins_stats = get_path(dubins_id, starts_without_curvature, goals_without_curvature);
710  computation_times.clear();
711  for (const auto& stat : dubins_stats)
712  {
713  computation_times.push_back(stat.computation_time);
714  }
715  cout << "[----------] " + dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
716  << get_std(computation_times) << endl;
717 
718  string cc00_rs_id = "CC00_RS";
719  vector<Statistic> cc00_rs_stats = get_path(cc00_rs_id, starts_without_curvature, goals_without_curvature);
720  computation_times.clear();
721  for (const auto& stat : cc00_rs_stats)
722  {
723  computation_times.push_back(stat.computation_time);
724  }
725  cout << "[----------] " + cc00_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
726  << get_std(computation_times) << endl;
727 
728  string hc_rs_id = "HC_RS";
729  vector<Statistic> hc_rs_stats = get_path(hc_rs_id, starts_with_curvature, goals_with_curvature);
730  computation_times.clear();
731  for (const auto& stat : hc_rs_stats)
732  {
733  computation_times.push_back(stat.computation_time);
734  }
735  cout << "[----------] " + hc_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
736  << get_std(computation_times) << endl;
737 
738  string hc00_rs_id = "HC00_RS";
739  vector<Statistic> hc00_rs_stats = get_path(hc00_rs_id, starts_without_curvature, goals_without_curvature);
740  computation_times.clear();
741  for (const auto& stat : hc00_rs_stats)
742  {
743  computation_times.push_back(stat.computation_time);
744  }
745  cout << "[----------] " + hc00_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
746  << get_std(computation_times) << endl;
747 
748  string hc0pm_rs_id = "HC0pm_RS";
749  vector<Statistic> hc0pm_rs_stats = get_path(hc0pm_rs_id, starts_without_curvature, goals_without_curvature);
750  computation_times.clear();
751  for (const auto& stat : hc0pm_rs_stats)
752  {
753  computation_times.push_back(stat.computation_time);
754  }
755  cout << "[----------] " + hc0pm_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
756  << get_std(computation_times) << endl;
757 
758  string hcpm0_rs_id = "HCpm0_RS";
759  vector<Statistic> hcpm0_rs_stats = get_path(hcpm0_rs_id, starts_without_curvature, goals_without_curvature);
760  computation_times.clear();
761  for (const auto& stat : hcpm0_rs_stats)
762  {
763  computation_times.push_back(stat.computation_time);
764  }
765  cout << "[----------] " + hcpm0_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
766  << get_std(computation_times) << endl;
767 
768  string hcpmpm_rs_id = "HCpmpm_RS";
769  vector<Statistic> hcpmpm_rs_stats = get_path(hcpmpm_rs_id, starts_without_curvature, goals_without_curvature);
770  computation_times.clear();
771  for (const auto& stat : hcpmpm_rs_stats)
772  {
773  computation_times.push_back(stat.computation_time);
774  }
775  cout << "[----------] " + hcpmpm_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
776  << get_std(computation_times) << endl;
777 
778  string rs_id = "RS";
779  vector<Statistic> rs_stats = get_path(rs_id, starts_without_curvature, goals_without_curvature);
780  computation_times.clear();
781  for (const auto& stat : rs_stats)
782  {
783  computation_times.push_back(stat.computation_time);
784  }
785  cout << "[----------] " + rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
786  << get_std(computation_times) << endl;
787 }
788 
789 TEST(Timing, getPathWithCovariance)
790 {
791  // set filter parameters
792  Motion_Noise motion_noise;
793  Measurement_Noise measurement_noise;
794  Controller controller;
795  motion_noise.alpha1 = ALPHA1;
796  motion_noise.alpha2 = ALPHA2;
797  motion_noise.alpha3 = ALPHA3;
798  motion_noise.alpha4 = ALPHA4;
799  measurement_noise.std_x = STD_X;
800  measurement_noise.std_y = STD_Y;
801  measurement_noise.std_theta = STD_THETA;
802  controller.k1 = K1;
803  controller.k2 = K2;
804  controller.k3 = K3;
805  cc_dubins_forwards_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
806  cc00_dubins_forwards_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
807  cc0pm_dubins_forwards_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
808  ccpm0_dubins_forwards_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
809  ccpmpm_dubins_forwards_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
810  dubins_forwards_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
811  dubins_backwards_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
812  cc00_rs_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
813  hc_rs_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
814  hc00_rs_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
815  hc0pm_rs_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
816  hcpm0_rs_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
817  hcpmpm_rs_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
818  rs_ss.set_filter_parameters(motion_noise, measurement_noise, controller);
819 
820  srand(0);
821  vector<double> computation_times;
822  computation_times.reserve(SAMPLES);
823  vector<State_With_Covariance> starts_with_curvature, starts_without_curvature;
824  starts_with_curvature.reserve(SAMPLES);
825  starts_without_curvature.reserve(SAMPLES);
826  vector<State> goals_with_curvature, goals_without_curvature;
827  goals_with_curvature.reserve(SAMPLES);
828  goals_without_curvature.reserve(SAMPLES);
829  for (int i = 0; i < SAMPLES; i++)
830  {
832  start.state = get_random_state();
833  start.covariance[0 + 4 * 0] = start.Sigma[0 + 4 * 0] = pow(STD_X, 2);
834  start.covariance[1 + 4 * 1] = start.Sigma[1 + 4 * 1] = pow(STD_Y, 2);
835  start.covariance[2 + 4 * 2] = start.Sigma[2 + 4 * 2] = pow(STD_THETA, 2);
836  State goal = get_random_state();
837  starts_with_curvature.push_back(start);
838  goals_with_curvature.push_back(goal);
839  start.state.kappa = 0.0;
840  goal.kappa = 0.0;
841  starts_without_curvature.push_back(start);
842  goals_without_curvature.push_back(goal);
843  }
844 
845  string cc_dubins_id = "CC_Dubins";
846  vector<Statistic> cc_dubins_stats =
847  get_path_with_covariance(cc_dubins_id, starts_with_curvature, goals_with_curvature);
848  computation_times.clear();
849  for (const auto& stat : cc_dubins_stats)
850  {
851  computation_times.push_back(stat.computation_time);
852  }
853  cout << "[----------] " + cc_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
854  << get_std(computation_times) << endl;
855 
856  string cc00_dubins_id = "CC00_Dubins";
857  vector<Statistic> cc00_dubins_stats =
858  get_path_with_covariance(cc00_dubins_id, starts_without_curvature, goals_without_curvature);
859  computation_times.clear();
860  for (const auto& stat : cc00_dubins_stats)
861  {
862  computation_times.push_back(stat.computation_time);
863  }
864  cout << "[----------] " + cc00_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
865  << get_std(computation_times) << endl;
866 
867  string cc0pm_dubins_id = "CC0pm_Dubins";
868  vector<Statistic> cc0pm_dubins_stats =
869  get_path_with_covariance(cc0pm_dubins_id, starts_without_curvature, goals_without_curvature);
870  computation_times.clear();
871  for (const auto& stat : cc0pm_dubins_stats)
872  {
873  computation_times.push_back(stat.computation_time);
874  }
875  cout << "[----------] " + cc0pm_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
876  << get_std(computation_times) << endl;
877 
878  string ccpm0_dubins_id = "CCpm0_Dubins";
879  vector<Statistic> ccpm0_dubins_stats =
880  get_path_with_covariance(ccpm0_dubins_id, starts_without_curvature, goals_without_curvature);
881  computation_times.clear();
882  for (const auto& stat : ccpm0_dubins_stats)
883  {
884  computation_times.push_back(stat.computation_time);
885  }
886  cout << "[----------] " + ccpm0_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
887  << get_std(computation_times) << endl;
888 
889  string ccpmpm_dubins_id = "CCpmpm_Dubins";
890  vector<Statistic> ccpmpm_dubins_stats =
891  get_path_with_covariance(ccpmpm_dubins_id, starts_without_curvature, goals_without_curvature);
892  computation_times.clear();
893  for (const auto& stat : ccpmpm_dubins_stats)
894  {
895  computation_times.push_back(stat.computation_time);
896  }
897  cout << "[----------] " + ccpmpm_dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
898  << get_std(computation_times) << endl;
899 
900  string dubins_id = "Dubins";
901  vector<Statistic> dubins_stats =
902  get_path_with_covariance(dubins_id, starts_without_curvature, goals_without_curvature);
903  computation_times.clear();
904  for (const auto& stat : dubins_stats)
905  {
906  computation_times.push_back(stat.computation_time);
907  }
908  cout << "[----------] " + dubins_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
909  << get_std(computation_times) << endl;
910 
911  string cc00_rs_id = "CC00_RS";
912  vector<Statistic> cc00_rs_stats =
913  get_path_with_covariance(cc00_rs_id, starts_without_curvature, goals_without_curvature);
914  computation_times.clear();
915  for (const auto& stat : cc00_rs_stats)
916  {
917  computation_times.push_back(stat.computation_time);
918  }
919  cout << "[----------] " + cc00_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
920  << get_std(computation_times) << endl;
921 
922  string hc_rs_id = "HC_RS";
923  vector<Statistic> hc_rs_stats = get_path_with_covariance(hc_rs_id, starts_with_curvature, goals_with_curvature);
924  computation_times.clear();
925  for (const auto& stat : hc_rs_stats)
926  {
927  computation_times.push_back(stat.computation_time);
928  }
929  cout << "[----------] " + hc_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
930  << get_std(computation_times) << endl;
931 
932  string hc00_rs_id = "HC00_RS";
933  vector<Statistic> hc00_rs_stats =
934  get_path_with_covariance(hc00_rs_id, starts_without_curvature, goals_without_curvature);
935  computation_times.clear();
936  for (const auto& stat : hc00_rs_stats)
937  {
938  computation_times.push_back(stat.computation_time);
939  }
940  cout << "[----------] " + hc00_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
941  << get_std(computation_times) << endl;
942 
943  string hc0pm_rs_id = "HC0pm_RS";
944  vector<Statistic> hc0pm_rs_stats =
945  get_path_with_covariance(hc0pm_rs_id, starts_without_curvature, goals_without_curvature);
946  computation_times.clear();
947  for (const auto& stat : hc0pm_rs_stats)
948  {
949  computation_times.push_back(stat.computation_time);
950  }
951  cout << "[----------] " + hc0pm_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
952  << get_std(computation_times) << endl;
953 
954  string hcpm0_rs_id = "HCpm0_RS";
955  vector<Statistic> hcpm0_rs_stats =
956  get_path_with_covariance(hcpm0_rs_id, starts_without_curvature, goals_without_curvature);
957  computation_times.clear();
958  for (const auto& stat : hcpm0_rs_stats)
959  {
960  computation_times.push_back(stat.computation_time);
961  }
962  cout << "[----------] " + hcpm0_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
963  << get_std(computation_times) << endl;
964 
965  string hcpmpm_rs_id = "HCpmpm_RS";
966  vector<Statistic> hcpmpm_rs_stats =
967  get_path_with_covariance(hcpmpm_rs_id, starts_without_curvature, goals_without_curvature);
968  computation_times.clear();
969  for (const auto& stat : hcpmpm_rs_stats)
970  {
971  computation_times.push_back(stat.computation_time);
972  }
973  cout << "[----------] " + hcpmpm_rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
974  << get_std(computation_times) << endl;
975 
976  string rs_id = "RS";
977  vector<Statistic> rs_stats = get_path_with_covariance(rs_id, starts_without_curvature, goals_without_curvature);
978  computation_times.clear();
979  for (const auto& stat : rs_stats)
980  {
981  computation_times.push_back(stat.computation_time);
982  }
983  cout << "[----------] " + rs_id + " mean [s] +/- std [s]: " << get_mean(computation_times) << " +/- "
984  << get_std(computation_times) << endl;
985 }
986 
987 int main(int argc, char** argv)
988 {
989  testing::InitGoogleTest(&argc, argv);
990  return RUN_ALL_TESTS();
991 }
plot_statistics.curv_discont
curv_discont
Definition: plot_statistics.py:189
OPERATING_REGION_Y
#define OPERATING_REGION_Y
Definition: timing_test.cpp:46
steering::CC00_Dubins_State_Space
An implementation of continuous curvature (CC) steer for a Dubins car with zero curvature at the star...
Definition: cc00_dubins_state_space.hpp:70
steering::Reeds_Shepp_State_Space::set_filter_parameters
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
Definition: reeds_shepp_state_space.cpp:535
steering::Dubins_State_Space::get_path
std::vector< State > get_path(const State &state1, const State &state2) const
Returns shortest path from state1 to state2 with curvature = kappa_.
Definition: dubins_state_space.cpp:291
steering::CC0pm_Dubins_State_Space
An implementation of continuous curvature (CC) steer for a Dubins car with zero curvature at the star...
Definition: cc0pm_dubins_state_space.hpp:69
ALPHA3
#define ALPHA3
Definition: timing_test.cpp:50
hc00_rs_ss
HC00_Reeds_Shepp_State_Space hc00_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
steering::State
Description of a kinematic car's state.
Definition: steering_functions.hpp:44
steering::Dubins_State_Space
An SE(2) state space where distance is measured by the length of Dubins curves. Note that this Dubins...
Definition: dubins_state_space.hpp:141
steering::HC_CC_State_Space::get_path
std::vector< State > get_path(const State &state1, const State &state2) const
Returns path from state1 to state2.
Definition: hc_cc_state_space.cpp:68
TEST
TEST(Timing, getControls)
Definition: timing_test.cpp:464
reeds_shepp_state_space.hpp
steering::CC00_Dubins_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: cc00_dubins_state_space.cpp:496
steering::CC0pm_Dubins_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: cc0pm_dubins_state_space.cpp:508
SAMPLES
#define SAMPLES
Definition: timing_test.cpp:44
steering::HCpmpm_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with either positive (p) or negative (n) max....
Definition: hcpmpm_reeds_shepp_state_space.hpp:74
steering::HC00_Reeds_Shepp_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: hc00_reeds_shepp_state_space.cpp:1762
steering::Controller::k1
double k1
Weight on longitudinal error.
Definition: steering_functions.hpp:124
STD_THETA
#define STD_THETA
Definition: timing_test.cpp:54
ccpm0_dubins_forwards_ss
CCpm0_Dubins_State_Space ccpm0_dubins_forwards_ss(KAPPA, SIGMA, DISCRETIZATION, true)
get_mean
double get_mean(const vector< double > &v)
Definition: timing_test.cpp:83
steering::Measurement_Noise::std_theta
double std_theta
Standard deviation of localization in theta.
Definition: steering_functions.hpp:117
steering::HC00_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with zero curvature at the start and goal configurat...
Definition: hc00_reeds_shepp_state_space.hpp:73
steering::Controller::k2
double k2
Weight on lateral error.
Definition: steering_functions.hpp:127
steering::State::theta
double theta
Orientation of the robot.
Definition: steering_functions.hpp:70
steering::CCpmpm_Dubins_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: ccpmpm_dubins_state_space.cpp:653
time.h
ALPHA1
#define ALPHA1
Definition: timing_test.cpp:48
KAPPA
#define KAPPA
Definition: timing_test.cpp:41
get_path_with_covariance
vector< Statistic > get_path_with_covariance(const string &id, const vector< State_With_Covariance > &starts, const vector< State > &goals)
Definition: timing_test.cpp:366
steering::Reeds_Shepp_State_Space::get_path_with_covariance
std::vector< State_With_Covariance > get_path_with_covariance(const State_With_Covariance &state1, const State &state2) const
Returns shortest path including covariances from state1 to state2 with curvature = kappa_.
Definition: reeds_shepp_state_space.cpp:586
steering::Motion_Noise::alpha2
double alpha2
Definition: steering_functions.hpp:100
K1
#define K1
Definition: timing_test.cpp:55
steering::Dubins_State_Space::set_filter_parameters
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
Definition: dubins_state_space.cpp:235
K2
#define K2
Definition: timing_test.cpp:56
hc_rs_ss
HC_Reeds_Shepp_State_Space hc_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
steering::HC0pm_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with zero curvature at the start configuration and e...
Definition: hc0pm_reeds_shepp_state_space.hpp:74
steering::HC_CC_State_Space::get_path_with_covariance
std::vector< State_With_Covariance > get_path_with_covariance(const State_With_Covariance &state1, const State &state2) const
Returns path including covariances from state1 to state2.
Definition: hc_cc_state_space.cpp:74
steering::Dubins_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2 with curvature = kappa_.
Definition: dubins_state_space.cpp:249
steering::State::kappa
double kappa
Curvature at position (x,y)
Definition: steering_functions.hpp:73
steering::CC00_Reeds_Shepp_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: cc00_reeds_shepp_state_space.cpp:1705
steering::CC0pm_Dubins_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: cc0pm_dubins_state_space.cpp:516
hc0pm_reeds_shepp_state_space.hpp
steering::CCpm0_Dubins_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: ccpm0_dubins_state_space.cpp:507
get_curv_discont
int get_curv_discont(const vector< Control > &controls)
Definition: timing_test.cpp:100
steering::HCpm0_Reeds_Shepp_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: hcpm0_reeds_shepp_state_space.cpp:1783
ALPHA4
#define ALPHA4
Definition: timing_test.cpp:51
steering::CC_Dubins_State_Space
An implementation of continuous curvature (CC) steer for a Dubins car with arbitrary curvature at the...
Definition: cc_dubins_state_space.hpp:54
steering::HC_Reeds_Shepp_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: hc_reeds_shepp_state_space.cpp:144
cc00_dubins_forwards_ss
CC00_Dubins_State_Space cc00_dubins_forwards_ss(KAPPA, SIGMA, DISCRETIZATION, true)
cc00_rs_ss
CC00_Reeds_Shepp_State_Space cc00_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
steering::HCpm0_Reeds_Shepp_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: hcpm0_reeds_shepp_state_space.cpp:1791
EPS_KAPPA
#define EPS_KAPPA
Definition: timing_test.cpp:40
steering::State::y
double y
Position in y of the robot.
Definition: steering_functions.hpp:67
cc0pm_dubins_forwards_ss
CC0pm_Dubins_State_Space cc0pm_dubins_forwards_ss(KAPPA, SIGMA, DISCRETIZATION, true)
ccpm0_dubins_state_space.hpp
steering::CC_Dubins_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: cc_dubins_state_space.cpp:97
steering::HC_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with arbitrary curvature at the start and goal confi...
Definition: hc_reeds_shepp_state_space.hpp:53
get_random_state
State get_random_state()
Definition: timing_test.cpp:72
steering::HC0pm_Reeds_Shepp_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: hc0pm_reeds_shepp_state_space.cpp:1785
steering::HC0pm_Reeds_Shepp_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: hc0pm_reeds_shepp_state_space.cpp:1793
steering::Reeds_Shepp_State_Space::get_path
std::vector< State > get_path(const State &state1, const State &state2) const
Returns shortest path from state1 to state2 with curvature = kappa_.
Definition: reeds_shepp_state_space.cpp:580
steering::CC00_Reeds_Shepp_State_Space
An implementation of continuous curvature (CC) steer for a Reeds-Shepp car with zero curvature at the...
Definition: cc00_reeds_shepp_state_space.hpp:74
steering::CCpm0_Dubins_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: ccpm0_dubins_state_space.cpp:515
Statistic::computation_time
double computation_time
Definition: timing_test.cpp:67
steering::Motion_Noise::alpha3
double alpha3
Variance in lateral direction: alpha3*delta_s*delta_s + alpha4*kappa*kappa.
Definition: steering_functions.hpp:103
steering::HC_Reeds_Shepp_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: hc_reeds_shepp_state_space.cpp:92
main
int main(int argc, char **argv)
Definition: timing_test.cpp:987
hc0pm_rs_ss
HC0pm_Reeds_Shepp_State_Space hc0pm_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
ALPHA2
#define ALPHA2
Definition: timing_test.cpp:49
hc00_reeds_shepp_state_space.hpp
ccpmpm_dubins_forwards_ss
CCpmpm_Dubins_State_Space ccpmpm_dubins_forwards_ss(KAPPA, SIGMA, DISCRETIZATION, true)
steering::HC_CC_State_Space::set_filter_parameters
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
Definition: hc_cc_state_space.cpp:62
steering::Motion_Noise
Parameters of the motion noise model according to the book: Probabilistic Robotics,...
Definition: steering_functions.hpp:96
steering::State::x
double x
Position in x of the robot.
Definition: steering_functions.hpp:64
DISCRETIZATION
#define DISCRETIZATION
Definition: timing_test.cpp:43
K3
#define K3
Definition: timing_test.cpp:57
STD_X
#define STD_X
Definition: timing_test.cpp:52
steering::Dubins_State_Space::get_path_with_covariance
std::vector< State_With_Covariance > get_path_with_covariance(const State_With_Covariance &state1, const State &state2) const
Returns shortest path including covariances from state1 to state2 with curvature = kappa_.
Definition: dubins_state_space.cpp:297
steering::HCpmpm_Reeds_Shepp_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: hcpmpm_reeds_shepp_state_space.cpp:1839
get_std
double get_std(const vector< double > &v)
Definition: timing_test.cpp:89
hcpm0_reeds_shepp_state_space.hpp
write_to_file
void write_to_file(const string &id, const vector< Statistic > &stats)
Definition: timing_test.cpp:113
steering::CCpm0_Dubins_State_Space
An implementation of continuous curvature (CC) steer for a Dubins car with either positive (p) or neg...
Definition: ccpm0_dubins_state_space.hpp:69
get_path
vector< Statistic > get_path(const string &id, const vector< State > &starts, const vector< State > &goals)
Definition: timing_test.cpp:271
steering::HCpm0_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with either positive (p) or negative (n) max....
Definition: hcpm0_reeds_shepp_state_space.hpp:74
Statistic::curv_discont
int curv_discont
Definition: timing_test.cpp:69
package.h
steering::Reeds_Shepp_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2 with curvature = kappa_.
Definition: reeds_shepp_state_space.cpp:547
get_controls
vector< Statistic > get_controls(const string &id, const vector< State > &starts, const vector< State > &goals)
Definition: timing_test.cpp:146
Statistic
Definition: timing_test.cpp:63
steering::CCpmpm_Dubins_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: ccpmpm_dubins_state_space.cpp:661
steering::HC00_Reeds_Shepp_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: hc00_reeds_shepp_state_space.cpp:1754
start
ROSCPP_DECL void start()
steering::CC00_Dubins_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: cc00_dubins_state_space.cpp:488
cc_dubins_forwards_ss
CC_Dubins_State_Space cc_dubins_forwards_ss(KAPPA, SIGMA, DISCRETIZATION, true)
steering::Controller::k3
double k3
Weight on heading error.
Definition: steering_functions.hpp:130
hc_reeds_shepp_state_space.hpp
steering::HCpmpm_Reeds_Shepp_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: hcpmpm_reeds_shepp_state_space.cpp:1831
std
steering::Motion_Noise::alpha4
double alpha4
Definition: steering_functions.hpp:104
steering_functions.hpp
dubins_backwards_ss
Dubins_State_Space dubins_backwards_ss(KAPPA, DISCRETIZATION, false)
steering::Measurement_Noise::std_y
double std_y
Standard deviation of localization in y.
Definition: steering_functions.hpp:114
steering::State_With_Covariance
Description of a kinematic car's state with covariance.
Definition: steering_functions.hpp:63
random
#define random(lower, upper)
Definition: timing_test.cpp:58
steering::Reeds_Shepp_State_Space
An SE(2) state space where distance is measured by the length of Reeds-Shepp curves....
Definition: reeds_shepp_state_space.hpp:141
steering::Controller
Parameters of the feedback controller.
Definition: steering_functions.hpp:121
ccpmpm_dubins_state_space.hpp
steering
Definition: dubins_state_space.hpp:70
hcpmpm_reeds_shepp_state_space.hpp
cc00_dubins_state_space.hpp
SIGMA
#define SIGMA
Definition: timing_test.cpp:42
STD_Y
#define STD_Y
Definition: timing_test.cpp:53
cc00_reeds_shepp_state_space.hpp
header
const std::string header
dubins_forwards_ss
Dubins_State_Space dubins_forwards_ss(KAPPA, DISCRETIZATION, true)
Statistic::start
State start
Definition: timing_test.cpp:65
steering::State::d
double d
Definition: steering_functions.hpp:76
steering::Measurement_Noise::std_x
double std_x
Standard deviation of localization in x.
Definition: steering_functions.hpp:111
dubins_state_space.hpp
steering::CC00_Reeds_Shepp_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: cc00_reeds_shepp_state_space.cpp:1697
Statistic::goal
State goal
Definition: timing_test.cpp:66
hcpm0_rs_ss
HCpm0_Reeds_Shepp_State_Space hcpm0_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
cc_dubins_state_space.hpp
steering::CC_Dubins_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
Definition: cc_dubins_state_space.cpp:149
rs_ss
Reeds_Shepp_State_Space rs_ss(KAPPA, DISCRETIZATION)
Statistic::path_length
double path_length
Definition: timing_test.cpp:68
steering::Motion_Noise::alpha1
double alpha1
Variance in longitudinal direction: alpha1*delta_s*delta_s + alpha2*kappa*kappa
Definition: steering_functions.hpp:99
hcpmpm_rs_ss
HCpmpm_Reeds_Shepp_State_Space hcpmpm_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
plot_states.f
f
Definition: plot_states.py:93
steering::Reeds_Shepp_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2 with curvature = kappa_.
Definition: reeds_shepp_state_space.cpp:542
OPERATING_REGION_THETA
#define OPERATING_REGION_THETA
Definition: timing_test.cpp:47
steering::Measurement_Noise
Parameters of the measurement noise.
Definition: steering_functions.hpp:108
steering::Dubins_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2 with curvature = kappa_.
Definition: dubins_state_space.cpp:241
steering::CCpmpm_Dubins_State_Space
An implementation of continuous curvature (CC) steer for a Dubins car with either positive (p) or neg...
Definition: ccpmpm_dubins_state_space.hpp:70
cc0pm_dubins_state_space.hpp
OPERATING_REGION_X
#define OPERATING_REGION_X
Definition: timing_test.cpp:45


steering_functions
Author(s): Holger Banzhaf
autogenerated on Mon Dec 11 2023 03:27:44