18 #include <gtest/gtest.h> 39 #define EPS_DISTANCE 0.01 // [m] 40 #define EPS_YAW 0.01 // [rad] 41 #define EPS_KAPPA 1e-6 // [1/m] 42 #define KAPPA 1.0 // [1/m] 43 #define SIGMA 1.0 // [1/m^2] 44 #define DISCRETIZATION 0.1 // [m] 45 #define SAMPLES 1e5 // [-] 46 #define OPERATING_REGION_X 20.0 // [m] 47 #define OPERATING_REGION_Y 20.0 // [m] 48 #define OPERATING_REGION_THETA 2 * M_PI // [rad] 49 #define random(lower, upper) (rand() * (upper - lower) / RAND_MAX + lower) 50 #define random_boolean() rand() % 2 68 return sqrt(
pow(state2.
x - state1.
x, 2) +
pow(state2.
y - state1.
y, 2));
73 double path_length = 0;
74 State state1 = path.front();
75 for (
const auto& state2 : path)
85 double path_length = 0;
86 for (
const auto& control : controls)
87 path_length += fabs(control.delta_s);
120 int seed(time(
nullptr));
122 TEST(SteeringFunctions, pathLength)
125 for (
int i = 0; i <
SAMPLES; i++)
142 vector<State> cc_dubins_path_forwards = cc_dubins_forwards_ss.
get_path(start, goal);
146 vector<State> cc_dubins_path_backwards = cc_dubins_backwards_ss.
get_path(start, goal);
150 vector<State> cc00_dubins_path_forwards = cc00_dubins_forwards_ss.
get_path(start, goal);
154 vector<State> cc00_dubins_path_backwards = cc00_dubins_backwards_ss.
get_path(start, goal);
158 vector<State> cc0pm_dubins_path_forwards = cc0pm_dubins_forwards_ss.
get_path(start, goal);
162 vector<State> cc0pm_dubins_path_backwards = cc0pm_dubins_backwards_ss.
get_path(start, goal);
166 vector<State> ccpm0_dubins_path_forwards = ccpm0_dubins_forwards_ss.
get_path(start, goal);
170 vector<State> ccpm0_dubins_path_backwards = ccpm0_dubins_backwards_ss.
get_path(start, goal);
174 vector<State> ccpmpm_dubins_path_forwards = ccpmpm_dubins_forwards_ss.
get_path(start, goal);
178 vector<State> ccpmpm_dubins_path_backwards = ccpmpm_dubins_backwards_ss.
get_path(start, goal);
183 vector<State> dubins_path_forwards = dubins_forwards_ss.
get_path(start, goal);
186 vector<State> dubins_path_backwards = dubins_backwards_ss.
get_path(start, goal);
190 vector<State> cc00_rs_path = cc00_rs_ss.
get_path(start, goal);
193 vector<State> hc_rs_path = hc_rs_ss.
get_path(start, goal);
196 vector<State> hc00_rs_path = hc00_rs_ss.
get_path(start, goal);
199 vector<State> hc0pm_rs_path = hc0pm_rs_ss.
get_path(start, goal);
202 vector<State> hcpm0_rs_path = hcpm0_rs_ss.
get_path(start, goal);
205 vector<State> hcpmpm_rs_path = hcpmpm_rs_ss.
get_path(start, goal);
208 vector<State> rs_path = rs_ss.
get_path(start, goal);
213 TEST(SteeringFunctions, reachingGoal)
216 for (
int i = 0; i <
SAMPLES; i++)
233 vector<State> cc_dubins_path_forwards = cc_dubins_forwards_ss.
get_path(start, goal);
236 vector<State> cc_dubins_path_backwards = cc_dubins_backwards_ss.
get_path(start, goal);
239 vector<State> cc00_dubins_path_forwards = cc00_dubins_forwards_ss.
get_path(start, goal);
242 vector<State> cc00_dubins_path_backwards = cc00_dubins_backwards_ss.
get_path(start, goal);
245 vector<State> cc0pm_dubins_path_forwards = cc0pm_dubins_forwards_ss.
get_path(start, goal);
248 vector<State> cc0pm_dubins_path_backwards = cc0pm_dubins_backwards_ss.
get_path(start, goal);
251 vector<State> ccpm0_dubins_path_forwards = ccpm0_dubins_forwards_ss.
get_path(start, goal);
254 vector<State> ccpm0_dubins_path_backwards = ccpm0_dubins_backwards_ss.
get_path(start, goal);
257 vector<State> ccpmpm_dubins_path_forwards = ccpmpm_dubins_forwards_ss.
get_path(start, goal);
260 vector<State> ccpmpm_dubins_path_backwards = ccpmpm_dubins_backwards_ss.
get_path(start, goal);
263 vector<State> dubins_path_forwards = dubins_forwards_ss.
get_path(start, goal);
266 vector<State> dubins_path_backwards = dubins_backwards_ss.
get_path(start, goal);
269 vector<State> cc00_rs_path = cc00_rs_ss.
get_path(start, goal);
272 vector<State> hc_rs_path = hc_rs_ss.
get_path(start, goal);
275 vector<State> hc00_rs_path = hc00_rs_ss.
get_path(start, goal);
278 vector<State> hc0pm_rs_path = hc0pm_rs_ss.
get_path(start, goal);
281 vector<State> hcpm0_rs_path = hcpm0_rs_ss.
get_path(start, goal);
284 vector<State> hcpmpm_rs_path = hcpmpm_rs_ss.
get_path(start, goal);
287 vector<State> rs_path = rs_ss.
get_path(start, goal);
292 TEST(SteeringFunctions, curvatureContinuity)
295 for (
int i = 0; i <
SAMPLES; i++)
314 vector<State> cc_dubins_forwards_path = cc_dubins_forwards_ss.
get_path(start, goal);
315 state1 = cc_dubins_forwards_path.front();
316 for (
const auto& state2 : cc_dubins_forwards_path)
322 vector<State> cc_dubins_backwards_path = cc_dubins_backwards_ss.
get_path(start, goal);
323 state1 = cc_dubins_backwards_path.front();
324 for (
const auto& state2 : cc_dubins_backwards_path)
330 vector<State> cc00_dubins_forwards_path = cc00_dubins_forwards_ss.
get_path(start, goal);
331 state1 = cc00_dubins_forwards_path.front();
332 for (
const auto& state2 : cc00_dubins_forwards_path)
338 vector<State> cc00_dubins_backwards_path = cc00_dubins_backwards_ss.
get_path(start, goal);
339 state1 = cc00_dubins_backwards_path.front();
340 for (
const auto& state2 : cc00_dubins_backwards_path)
346 vector<State> cc0pm_dubins_forwards_path = cc0pm_dubins_forwards_ss.
get_path(start, goal);
347 state1 = cc0pm_dubins_forwards_path.front();
348 for (
const auto& state2 : cc0pm_dubins_forwards_path)
354 vector<State> cc0pm_dubins_backwards_path = cc0pm_dubins_backwards_ss.
get_path(start, goal);
355 state1 = cc0pm_dubins_backwards_path.front();
356 for (
const auto& state2 : cc0pm_dubins_backwards_path)
362 vector<State> ccpm0_dubins_forwards_path = ccpm0_dubins_forwards_ss.
get_path(start, goal);
363 state1 = ccpm0_dubins_forwards_path.front();
364 for (
const auto& state2 : ccpm0_dubins_forwards_path)
370 vector<State> ccpm0_dubins_backwards_path = ccpm0_dubins_backwards_ss.
get_path(start, goal);
371 state1 = ccpm0_dubins_backwards_path.front();
372 for (
const auto& state2 : ccpm0_dubins_backwards_path)
378 vector<State> ccpmpm_dubins_forwards_path = ccpmpm_dubins_forwards_ss.
get_path(start, goal);
379 state1 = ccpmpm_dubins_forwards_path.front();
380 for (
const auto& state2 : ccpmpm_dubins_forwards_path)
386 vector<State> ccpmpm_dubins_backwards_path = ccpmpm_dubins_backwards_ss.
get_path(start, goal);
387 state1 = ccpmpm_dubins_backwards_path.front();
388 for (
const auto& state2 : ccpmpm_dubins_backwards_path)
394 vector<State> cc00_rs_path = cc00_rs_ss.
get_path(start, goal);
395 state1 = cc00_rs_path.front();
396 for (
const auto& state2 : cc00_rs_path)
402 vector<State> hc_rs_path = hc_rs_ss.
get_path(start, goal);
403 state1 = hc_rs_path.front();
404 for (
const auto& state2 : hc_rs_path)
406 if (state1.
d * state2.d >= 0)
413 vector<State> hc00_rs_path = hc00_rs_ss.
get_path(start, goal);
414 state1 = hc00_rs_path.front();
415 for (
const auto& state2 : hc00_rs_path)
417 if (state1.
d * state2.d >= 0)
424 vector<State> hc0pm_rs_path = hc0pm_rs_ss.
get_path(start, goal);
425 state1 = hc0pm_rs_path.front();
426 for (
const auto& state2 : hc0pm_rs_path)
428 if (state1.
d * state2.d >= 0)
435 vector<State> hcpm0_rs_path = hcpm0_rs_ss.
get_path(start, goal);
436 state1 = hcpm0_rs_path.front();
437 for (
const auto& state2 : hcpm0_rs_path)
439 if (state1.
d * state2.d >= 0)
446 vector<State> hcpmpm_rs_path = hcpmpm_rs_ss.
get_path(start, goal);
447 state1 = hcpmpm_rs_path.front();
448 for (
const auto& state2 : hcpmpm_rs_path)
450 if (state1.
d * state2.d >= 0)
459 TEST(SteeringFunctions, interpolation)
463 for (
int i = 0; i <
SAMPLES; i++)
465 double t = ((double)rand() / (RAND_MAX));
481 vector<Control> cc_dubins_forwards_controls = cc_dubins_forwards_ss.
get_controls(start, goal);
482 double cc_dubins_forwards_s_path =
get_path_length(cc_dubins_forwards_controls);
483 double cc_dubins_forwards_s_inter = t * cc_dubins_forwards_s_path;
485 vector<Control> cc_dubins_forwards_controls_inter;
486 cc_dubins_forwards_controls_inter.reserve(cc_dubins_forwards_controls.size());
487 for (
const auto& control : cc_dubins_forwards_controls)
489 double abs_delta_s = fabs(control.delta_s);
491 if (s < cc_dubins_forwards_s_inter)
492 cc_dubins_forwards_controls_inter.push_back(control);
496 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - cc_dubins_forwards_s_inter));
497 control_inter.
kappa = control.kappa;
498 control_inter.
sigma = control.sigma;
499 cc_dubins_forwards_controls_inter.push_back(control_inter);
503 vector<State> cc_dubins_forwards_path = cc_dubins_forwards_ss.
integrate(start, cc_dubins_forwards_controls_inter);
504 State cc_dubins_forwards_state_inter = cc_dubins_forwards_ss.
interpolate(start, cc_dubins_forwards_controls, t);
505 EXPECT_EQ(
is_equal(cc_dubins_forwards_path.back(), cc_dubins_forwards_state_inter),
true);
507 vector<Control> cc00_dubins_forwards_controls = cc00_dubins_forwards_ss.
get_controls(start, goal);
508 double cc00_dubins_forwards_s_path =
get_path_length(cc00_dubins_forwards_controls);
509 double cc00_dubins_forwards_s_inter = t * cc00_dubins_forwards_s_path;
511 vector<Control> cc00_dubins_forwards_controls_inter;
512 cc00_dubins_forwards_controls_inter.reserve(cc00_dubins_forwards_controls.size());
513 for (
const auto& control : cc00_dubins_forwards_controls)
515 double abs_delta_s = fabs(control.delta_s);
517 if (s < cc00_dubins_forwards_s_inter)
518 cc00_dubins_forwards_controls_inter.push_back(control);
522 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - cc00_dubins_forwards_s_inter));
523 control_inter.
kappa = control.kappa;
524 control_inter.
sigma = control.sigma;
525 cc00_dubins_forwards_controls_inter.push_back(control_inter);
529 vector<State> cc00_dubins_forwards_path =
530 cc00_dubins_forwards_ss.
integrate(start, cc00_dubins_forwards_controls_inter);
531 State cc00_dubins_forwards_state_inter =
532 cc00_dubins_forwards_ss.
interpolate(start, cc00_dubins_forwards_controls, t);
533 EXPECT_EQ(
is_equal(cc00_dubins_forwards_path.back(), cc00_dubins_forwards_state_inter),
true);
535 vector<Control> cc0pm_dubins_forwards_controls = cc0pm_dubins_forwards_ss.
get_controls(start, goal);
536 double cc0pm_dubins_forwards_s_path =
get_path_length(cc0pm_dubins_forwards_controls);
537 double cc0pm_dubins_forwards_s_inter = t * cc0pm_dubins_forwards_s_path;
539 vector<Control> cc0pm_dubins_forwards_controls_inter;
540 cc0pm_dubins_forwards_controls_inter.reserve(cc0pm_dubins_forwards_controls.size());
541 for (
const auto& control : cc0pm_dubins_forwards_controls)
543 double abs_delta_s = fabs(control.delta_s);
545 if (s < cc0pm_dubins_forwards_s_inter)
546 cc0pm_dubins_forwards_controls_inter.push_back(control);
550 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - cc0pm_dubins_forwards_s_inter));
551 control_inter.
kappa = control.kappa;
552 control_inter.
sigma = control.sigma;
553 cc0pm_dubins_forwards_controls_inter.push_back(control_inter);
557 vector<State> cc0pm_dubins_forwards_path =
558 cc0pm_dubins_forwards_ss.
integrate(start, cc0pm_dubins_forwards_controls_inter);
559 State cc0pm_dubins_forwards_state_inter =
560 cc0pm_dubins_forwards_ss.
interpolate(start, cc0pm_dubins_forwards_controls, t);
561 EXPECT_EQ(
is_equal(cc0pm_dubins_forwards_path.back(), cc0pm_dubins_forwards_state_inter),
true);
563 vector<Control> ccpm0_dubins_forwards_controls = ccpm0_dubins_forwards_ss.
get_controls(start, goal);
564 double ccpm0_dubins_forwards_s_path =
get_path_length(ccpm0_dubins_forwards_controls);
565 double ccpm0_dubins_forwards_s_inter = t * ccpm0_dubins_forwards_s_path;
567 vector<Control> ccpm0_dubins_forwards_controls_inter;
568 ccpm0_dubins_forwards_controls_inter.reserve(ccpm0_dubins_forwards_controls.size());
569 for (
const auto& control : ccpm0_dubins_forwards_controls)
571 double abs_delta_s = fabs(control.delta_s);
573 if (s < ccpm0_dubins_forwards_s_inter)
574 ccpm0_dubins_forwards_controls_inter.push_back(control);
578 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - ccpm0_dubins_forwards_s_inter));
579 control_inter.
kappa = control.kappa;
580 control_inter.
sigma = control.sigma;
581 ccpm0_dubins_forwards_controls_inter.push_back(control_inter);
585 vector<State> ccpm0_dubins_forwards_path =
586 ccpm0_dubins_forwards_ss.
integrate(start, ccpm0_dubins_forwards_controls_inter);
587 State ccpm0_dubins_forwards_state_inter =
588 ccpm0_dubins_forwards_ss.
interpolate(start, ccpm0_dubins_forwards_controls, t);
589 EXPECT_EQ(
is_equal(ccpm0_dubins_forwards_path.back(), ccpm0_dubins_forwards_state_inter),
true);
591 vector<Control> ccpmpm_dubins_forwards_controls = ccpmpm_dubins_forwards_ss.
get_controls(start, goal);
592 double ccpmpm_dubins_forwards_s_path =
get_path_length(ccpmpm_dubins_forwards_controls);
593 double ccpmpm_dubins_forwards_s_inter = t * ccpmpm_dubins_forwards_s_path;
595 vector<Control> ccpmpm_dubins_forwards_controls_inter;
596 ccpmpm_dubins_forwards_controls_inter.reserve(ccpmpm_dubins_forwards_controls.size());
597 for (
const auto& control : ccpmpm_dubins_forwards_controls)
599 double abs_delta_s = fabs(control.delta_s);
601 if (s < ccpmpm_dubins_forwards_s_inter)
602 ccpmpm_dubins_forwards_controls_inter.push_back(control);
606 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - ccpmpm_dubins_forwards_s_inter));
607 control_inter.
kappa = control.kappa;
608 control_inter.
sigma = control.sigma;
609 ccpmpm_dubins_forwards_controls_inter.push_back(control_inter);
613 vector<State> ccpmpm_dubins_forwards_path =
614 ccpmpm_dubins_forwards_ss.
integrate(start, ccpmpm_dubins_forwards_controls_inter);
615 State ccpmpm_dubins_forwards_state_inter =
616 ccpmpm_dubins_forwards_ss.
interpolate(start, ccpmpm_dubins_forwards_controls, t);
617 EXPECT_EQ(
is_equal(ccpmpm_dubins_forwards_path.back(), ccpmpm_dubins_forwards_state_inter),
true);
619 vector<Control> dubins_forwards_controls = dubins_forwards_ss.
get_controls(start, goal);
620 double dubins_forwards_s_path =
get_path_length(dubins_forwards_controls);
621 double dubins_forwards_s_inter = t * dubins_forwards_s_path;
623 vector<Control> dubins_forwards_controls_inter;
624 dubins_forwards_controls_inter.reserve(dubins_forwards_controls.size());
625 for (
const auto& control : dubins_forwards_controls)
627 double abs_delta_s = fabs(control.delta_s);
629 if (s < dubins_forwards_s_inter)
630 dubins_forwards_controls_inter.push_back(control);
634 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - dubins_forwards_s_inter));
635 control_inter.
kappa = control.kappa;
636 control_inter.
sigma = control.sigma;
637 dubins_forwards_controls_inter.push_back(control_inter);
641 vector<State> dubins_forwards_path = dubins_forwards_ss.
integrate(start, dubins_forwards_controls_inter);
642 State dubins_forwards_state_inter = dubins_forwards_ss.
interpolate(start, dubins_forwards_controls, t);
643 EXPECT_EQ(
is_equal(dubins_forwards_path.back(), dubins_forwards_state_inter),
true);
645 vector<Control> cc00_rs_controls = cc00_rs_ss.
get_controls(start, goal);
647 double cc00_rs_s_inter = t * cc00_rs_s_path;
649 vector<Control> cc00_rs_controls_inter;
650 cc00_rs_controls_inter.reserve(cc00_rs_controls.size());
651 for (
const auto& control : cc00_rs_controls)
653 double abs_delta_s = fabs(control.delta_s);
655 if (s < cc00_rs_s_inter)
656 cc00_rs_controls_inter.push_back(control);
660 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - cc00_rs_s_inter));
661 control_inter.
kappa = control.kappa;
662 control_inter.
sigma = control.sigma;
663 cc00_rs_controls_inter.push_back(control_inter);
667 vector<State> cc00_rs_path = cc00_rs_ss.
integrate(start, cc00_rs_controls_inter);
668 State cc00_rs_state_inter = cc00_rs_ss.
interpolate(start, cc00_rs_controls, t);
669 EXPECT_EQ(
is_equal(cc00_rs_path.back(), cc00_rs_state_inter),
true);
671 vector<Control> hc_rs_controls = hc_rs_ss.
get_controls(start, goal);
673 double hc_rs_s_inter = t * hc_rs_s_path;
675 vector<Control> hc_rs_controls_inter;
676 hc_rs_controls_inter.reserve(hc_rs_controls.size());
677 for (
const auto& control : hc_rs_controls)
679 double abs_delta_s = fabs(control.delta_s);
681 if (s < hc_rs_s_inter)
682 hc_rs_controls_inter.push_back(control);
686 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - hc_rs_s_inter));
687 control_inter.
kappa = control.kappa;
688 control_inter.
sigma = control.sigma;
689 hc_rs_controls_inter.push_back(control_inter);
693 vector<State> hc_rs_path = hc_rs_ss.
integrate(start, hc_rs_controls_inter);
695 EXPECT_EQ(
is_equal(hc_rs_path.back(), hc_rs_state_inter),
true);
697 vector<Control> hc00_rs_controls = hc00_rs_ss.
get_controls(start, goal);
699 double hc00_rs_s_inter = t * hc00_rs_s_path;
701 vector<Control> hc00_rs_controls_inter;
702 hc00_rs_controls_inter.reserve(hc00_rs_controls.size());
703 for (
const auto& control : hc00_rs_controls)
705 double abs_delta_s = fabs(control.delta_s);
707 if (s < hc00_rs_s_inter)
708 hc00_rs_controls_inter.push_back(control);
712 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - hc00_rs_s_inter));
713 control_inter.
kappa = control.kappa;
714 control_inter.
sigma = control.sigma;
715 hc00_rs_controls_inter.push_back(control_inter);
719 vector<State> hc00_rs_path = hc00_rs_ss.
integrate(start, hc00_rs_controls_inter);
720 State hc00_rs_state_inter = hc00_rs_ss.
interpolate(start, hc00_rs_controls, t);
721 EXPECT_EQ(
is_equal(hc00_rs_path.back(), hc00_rs_state_inter),
true);
723 vector<Control> hcpmpm_rs_controls = hcpmpm_rs_ss.
get_controls(start, goal);
725 double hcpmpm_rs_s_inter = t * hcpmpm_rs_s_path;
727 vector<Control> hcpmpm_rs_controls_inter;
728 hcpmpm_rs_controls_inter.reserve(hcpmpm_rs_controls.size());
729 for (
const auto& control : hcpmpm_rs_controls)
731 double abs_delta_s = fabs(control.delta_s);
733 if (s < hcpmpm_rs_s_inter)
734 hcpmpm_rs_controls_inter.push_back(control);
738 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - hcpmpm_rs_s_inter));
739 control_inter.
kappa = control.kappa;
740 control_inter.
sigma = control.sigma;
741 hcpmpm_rs_controls_inter.push_back(control_inter);
745 vector<State> hcpmpm_rs_path = hcpmpm_rs_ss.
integrate(start, hcpmpm_rs_controls_inter);
746 State hcpmpm_rs_state_inter = hcpmpm_rs_ss.
interpolate(start, hcpmpm_rs_controls, t);
747 EXPECT_EQ(
is_equal(hcpmpm_rs_path.back(), hcpmpm_rs_state_inter),
true);
749 vector<Control> rs_controls = rs_ss.
get_controls(start, goal);
751 double rs_s_inter = t * rs_s_path;
753 vector<Control> rs_controls_inter;
754 rs_controls_inter.reserve(rs_controls.size());
755 for (
const auto& control : rs_controls)
757 double abs_delta_s = fabs(control.delta_s);
760 rs_controls_inter.push_back(control);
764 control_inter.
delta_s =
sgn(control.delta_s) * (abs_delta_s - (s - rs_s_inter));
765 control_inter.
kappa = control.kappa;
766 control_inter.
sigma = control.sigma;
767 rs_controls_inter.push_back(control_inter);
771 vector<State> rs_path = rs_ss.
integrate(start, rs_controls_inter);
773 EXPECT_EQ(
is_equal(rs_path.back(), rs_state_inter),
true);
777 TEST(SteeringFunctions, symmetry)
780 for (
int i = 0; i <
SAMPLES; ++i)
785 double cc00_rs_distance_forwards = cc00_rs_ss.
get_distance(start, goal);
786 double cc00_rs_distance_backwards = cc00_rs_ss.
get_distance(goal, start);
787 EXPECT_LT(fabs(cc00_rs_distance_forwards - cc00_rs_distance_backwards),
EPS_DISTANCE);
789 double hc00_rs_distance_forwards = hc00_rs_ss.
get_distance(start, goal);
790 double hc00_rs_distance_backwards = hc00_rs_ss.
get_distance(goal, start);
791 EXPECT_LT(fabs(hc00_rs_distance_forwards - hc00_rs_distance_backwards),
EPS_DISTANCE);
793 double hcpmpm_rs_distance_forwards = hcpmpm_rs_ss.
get_distance(start, goal);
794 double hcpmpm_rs_distance_backwards = hcpmpm_rs_ss.
get_distance(goal, start);
795 EXPECT_LT(fabs(hcpmpm_rs_distance_forwards - hcpmpm_rs_distance_backwards),
EPS_DISTANCE);
797 double rs_distance_forwards = rs_ss.
get_distance(start, goal);
798 double rs_distance_backwards = rs_ss.
get_distance(goal, start);
799 EXPECT_LT(fabs(rs_distance_forwards - rs_distance_backwards),
EPS_DISTANCE);
803 int main(
int argc,
char** argv)
805 testing::InitGoogleTest(&argc, argv);
806 return RUN_ALL_TESTS();
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
std::vector< State > get_path(const State &state1, const State &state2) const
Returns shortest path from state1 to state2 with curvature = kappa_.
std::vector< State > integrate(const State &state, const std::vector< Control > &controls) const
Returns integrated states given a start state and controls with curvature = kappa_.
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
CC0pm_Dubins_State_Space cc0pm_dubins_backwards_ss(KAPPA, SIGMA, DISCRETIZATION, false)
An implementation of continuous curvature (CC) steer for a Reeds-Shepp car with zero curvature at the...
HC00_Reeds_Shepp_State_Space hc00_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
An implementation of hybrid curvature (HC) steer with arbitrary curvature at the start and goal confi...
int main(int argc, char **argv)
double sgn(double x)
Return sign of a number.
An implementation of continuous curvature (CC) steer for a Dubins car with zero curvature at the star...
An implementation of hybrid curvature (HC) steer with zero curvature at the start and goal configurat...
HCpmpm_Reeds_Shepp_State_Space hcpmpm_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
#define OPERATING_REGION_X
State interpolate(const State &state, const std::vector< Control > &controls, double t) const
Returns interpolated state at distance t in [0,1] (percent of total path length with curvature = kapp...
double delta_s
Signed arc length of a segment.
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
#define OPERATING_REGION_Y
double kappa
Curvature at the beginning of a segment.
std::vector< State > integrate(const State &state, const std::vector< Control > &controls) const
Returns integrated states given a start state and controls with curvature = kappa_.
An implementation of continuous curvature (CC) steer for a Dubins car with either positive (p) or neg...
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
CCpm0_Dubins_State_Space ccpm0_dubins_backwards_ss(KAPPA, SIGMA, DISCRETIZATION, false)
An implementation of hybrid curvature (HC) steer with either positive (p) or negative (n) max...
State interpolate(const State &state, const std::vector< Control > &controls, double t) const
Returns interpolated state at distance t in [0,1] (percentage of total path length) ...
An implementation of hybrid curvature (HC) steer with either positive (p) or negative (n) max...
geometry_msgs::TransformStamped t
An implementation of continuous curvature (CC) steer for a Dubins car with arbitrary curvature at the...
An SE(2) state space where distance is measured by the length of Reeds-Shepp curves. The notation and solutions are taken from: J.A. Reeds and L.A. Shepp, “Optimal paths for a car that goes both forwards and backwards,” Pacific Journal of Mathematics, 145(2):367–393, 1990. This implementation explicitly computes all 48 Reeds-Shepp curves and returns the shortest valid solution. This can be improved by using the configuration space partition described in: P. Souères and J.-P. Laumond, “Shortest paths synthesis for a car-like robot,” IEEE Trans. on Automatic Control, 41(5):672–688, May 1996.
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
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_.
#define OPERATING_REGION_THETA
HCpm0_Reeds_Shepp_State_Space hcpm0_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
CCpm0_Dubins_State_Space ccpm0_dubins_forwards_ss(KAPPA, SIGMA, DISCRETIZATION, true)
Description of a path segment with its corresponding control inputs.
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
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_.
std::vector< State > integrate(const State &state, const std::vector< Control > &controls) const
Returns integrated states given a start state and controls.
double x
Position in x of the robot.
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
CC0pm_Dubins_State_Space cc0pm_dubins_forwards_ss(KAPPA, SIGMA, DISCRETIZATION, true)
double get_path_length(const vector< State > &path)
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2 with curvature = kappa_.
double get_distance(const State &state1, const State &state2)
#define random(lower, upper)
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
State interpolate(const State &state, const std::vector< Control > &controls, double t) const
Returns interpolated state at distance t in [0,1] (percent of total path length with curvature = kapp...
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
CCpmpm_Dubins_State_Space ccpmpm_dubins_backwards_ss(KAPPA, SIGMA, DISCRETIZATION, false)
Reeds_Shepp_State_Space rs_ss(KAPPA, DISCRETIZATION)
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
TEST(SteeringFunctions, pathLength)
An implementation of continuous curvature (CC) steer for a Dubins car with either positive (p) or neg...
CC_Dubins_State_Space cc_dubins_forwards_ss(KAPPA, SIGMA, DISCRETIZATION, true)
Description of a kinematic car's state.
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
Dubins_State_Space dubins_forwards_ss(KAPPA, DISCRETIZATION, true)
std::vector< State > get_path(const State &state1, const State &state2) const
Returns shortest path from state1 to state2 with curvature = kappa_.
bool is_equal(const State &state1, const State &state2)
An SE(2) state space where distance is measured by the length of Dubins curves. Note that this Dubins...
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
double sigma
Sharpness (derivative of curvature with respect to arc length) of a segment.
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
An implementation of continuous curvature (CC) steer for a Dubins car with zero curvature at the star...
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
double kappa
Curvature at position (x,y)
HC_Reeds_Shepp_State_Space hc_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
CC00_Dubins_State_Space cc00_dubins_forwards_ss(KAPPA, SIGMA, DISCRETIZATION, true)
CC00_Reeds_Shepp_State_Space cc00_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
CCpmpm_Dubins_State_Space ccpmpm_dubins_forwards_ss(KAPPA, SIGMA, DISCRETIZATION, true)
std::vector< State > get_path(const State &state1, const State &state2) const
Returns path from state1 to state2.
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
HC0pm_Reeds_Shepp_State_Space hc0pm_rs_ss(KAPPA, SIGMA, DISCRETIZATION)
Dubins_State_Space dubins_backwards_ss(KAPPA, DISCRETIZATION, false)
CC_Dubins_State_Space cc_dubins_backwards_ss(KAPPA, SIGMA, DISCRETIZATION, false)
double y
Position in y of the robot.
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2 with curvature = kappa_.
double theta
Orientation of the robot.
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
An implementation of hybrid curvature (HC) steer with zero curvature at the start configuration and e...
CC00_Dubins_State_Space cc00_dubins_backwards_ss(KAPPA, SIGMA, DISCRETIZATION, false)