dubins_cc_test.cpp
Go to the documentation of this file.
1 //=============================================================================
2 // Copyright (C) 2021-2024 Wageningen University - All Rights Reserved
3 // Author: Gonzalo Mier
4 // BSD-3 License
5 //=============================================================================
6 
7 #include <gtest/gtest.h>
8 #include <numeric>
9 #include <fstream>
10 #include "fields2cover.h"
11 #include "../test_helpers/path_planning_checker.hpp"
12 
13 
14 TEST(fields2cover_pp_dubins_cc, turn_dist) {
16  robot.setCruiseVel(2.0);
17  robot.setMaxCurv(1.0);
18  robot.setMaxDiffCurv(2.0);
19 
21  F2CPoint start(0.0, 0.0), end(-3.0, 0.0);
22  const double pi_2 { boost::math::constants::half_pi<double>()};
23  auto path = turn.createTurn(robot, start, pi_2, end, 3.0 * pi_2);
24 
25  EXPECT_TRUE(IsPathCorrect(path, start, pi_2, end, 3.0 * pi_2));
26 }
27 
28 TEST(fields2cover_pp_dubins_cc, random_points) {
30  robot.setCruiseVel(2.0);
31  robot.setMaxCurv(1.0);
32  robot.setMaxDiffCurv(1.0);
34  EXPECT_TRUE(turn.getUsingCache());
35  turn.setUsingCache(false);
36  EXPECT_FALSE(turn.getUsingCache());
37 
38  for (double ang = 0.25; ang < boost::math::constants::pi<double>(); ang += 0.25) {
39  F2CPoint start(0.0, 0.0), end(4.0, 0.0);
40  auto path = turn.createTurn(robot, start, ang,
41  end, ang + boost::math::constants::pi<double>());
42  EXPECT_TRUE(IsPathCorrect(path, start, ang,
43  end, ang + boost::math::constants::pi<double>()));
44  }
45 }
46 
2_objective_functions.path
path
Definition: 2_objective_functions.py:88
f2c::pp::TurningBase::getUsingCache
bool getUsingCache() const
Get if turns are being cached or not.
Definition: turning_base.cpp:122
f2c::pp::DubinsCurvesCC
Dubins' curves planner with continuous curves.
Definition: dubins_curves_cc.h:17
1_basic_types.end
end
Definition: 1_basic_types.py:76
2_objective_functions.robot
robot
Definition: 2_objective_functions.py:76
fields2cover.h
f2c::types::Point
Definition: Point.h:21
f2c::types::Robot
Definition: Robot.h:25
TEST
TEST(fields2cover_pp_dubins_cc, turn_dist)
Definition: dubins_cc_test.cpp:14
f2c::pp::TurningBase::setUsingCache
void setUsingCache(bool c)
Set if cache should be used when planning same turn as before.
Definition: turning_base.cpp:126
f2c::pp::TurningBase::createTurn
F2CPath createTurn(const F2CRobot &robot, const F2CPoint &start_pos, double start_angle, const F2CPoint &end_pos, double end_angle)
Create a turn that goes from one point with a certain angle to another point.
Definition: turning_base.cpp:30
IsPathCorrect
testing::AssertionResult IsPathCorrect(const F2CPath &path, F2CPoint start, double start_ang, F2CPoint end, double end_ang, bool check_y_lower_limit=true)
Definition: path_planning_checker.hpp:57


fields2cover
Author(s):
autogenerated on Fri Apr 25 2025 02:18:31