fields2cover.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 <utility>
8 #include "fields2cover.h"
9 
10 namespace f2c {
11 
12 /*
13 std::unique_ptr<f2c::decomp::DecompositionBase> getDecompPtr(const Options& opt) {
14  std::unique_ptr<f2c::decomp::DecompositionBase> ptr;
15  switch (opt.decomp_alg) {
16  case DecompAlg::TRAPEZOIDAL: {
17  decomp::TrapezoidalDecomp trap_decomp;
18  trap_decomp.setSplitAngle(opt.decomp_angle);
19  ptr = std::make_unique<decomp::TrapezoidalDecomp>(trap_decomp);
20  break;
21  }
22  case DecompAlg::BOUSTROPHEDON: {
23  decomp::BoustrophedonDecomp boustrophedon_decomp;
24  boustrophedon_decomp.setSplitAngle(opt.decomp_angle);
25  ptr = std::make_unique<decomp::BoustrophedonDecomp>(
26  boustrophedon_decomp);
27  break;
28  }
29  default:
30  break;
31  }
32  return ptr;
33 }
34 */
35 
36 std::unique_ptr<obj::SGObjective> getSGObjPtr(const Options& opt) {
37  std::unique_ptr<obj::SGObjective> ptr;
38  switch (opt.sg_obj) {
40  ptr = std::make_unique<obj::NSwathModified>();
41  break;
42  case SGObjFunc::N_SWATH:
43  ptr = std::make_unique<obj::NSwath>();
44  break;
46  ptr = std::make_unique<obj::SwathLength>();
47  break;
49  ptr = std::make_unique<obj::FieldCoverage>();
50  break;
52  ptr = std::make_unique<obj::Overlaps>();
53  break;
54  }
55  return ptr;
56 }
57 
58 std::unique_ptr<f2c::pp::TurningBase> getPPTurningBasePtr(const Options& opt) {
59  std::unique_ptr<f2c::pp::TurningBase> turn_planner;
60  switch (opt.pp_alg) {
61  case PPAlg::DUBINS:
62  turn_planner = std::make_unique<f2c::pp::DubinsCurves>();
63  break;
64  case PPAlg::DUBINS_CC:
65  turn_planner = std::make_unique<f2c::pp::DubinsCurvesCC>();
66  break;
67  case PPAlg::REEDS_SHEPP:
68  turn_planner = std::make_unique<f2c::pp::ReedsSheppCurves>();
69  break;
71  turn_planner = std::make_unique<f2c::pp::ReedsSheppCurvesHC>();
72  break;
73  }
74  return turn_planner;
75 }
76 
77 
78 
79 
80 
82  const Options& opt) {
83  return planCovRoute(robot, F2CCells(cell), opt);
84 }
85 
87  const Options& opt) {
88  F2CCells mainland;
89  F2CCells fast_hl_rings;
90  switch (opt.hg_alg) {
91  case HGAlg::NONE:
92  mainland = cells;
93  fast_hl_rings = cells;
94  break;
95  case HGAlg::CONST: {
97  mainland = const_hl.generateHeadlandArea(
98  cells, robot.getWidth(), opt.hg_swaths);
99  auto hl_swaths = const_hl.generateHeadlandSwaths(
100  cells, robot.getWidth(), opt.hg_swaths);
101  fast_hl_rings = hl_swaths[floor(0.5*opt.hg_swaths)];
102  break;
103  }
104  }
105 
108  switch (opt.sg_alg) {
109  case SGAlg::BRUTE_FORCE:
110  swaths = bf.generateBestSwaths(
111  *getSGObjPtr(opt), robot.getCovWidth(), mainland);
112  break;
113  case SGAlg::GIVEN_ANGLE:
114  swaths = bf.generateSwaths(
115  opt.sg_angle, robot.getCovWidth(), mainland);
116  }
118  return rp.genRoute(fast_hl_rings, swaths);
119 }
120 
122  bool local_crs) {
123  return planCovRoute(robot, field, Options(), local_crs);
124 }
125 
127  const Options& opt, bool local_crs) {
128  F2CField field_c = field.clone();
129  if (!local_crs) {
131  }
132  F2CRoute route = planCovRoute(robot, field_c.getField(), opt);
133  return local_crs ? route : f2c::Transform::transformToPrevCRS(route, field_c);
134 }
135 
137  const Options& opt) {
140 }
141 
143  const Options& opt) {
146 }
147 
149  bool local_crs) {
150  return planCovPath(robot, field, Options(), local_crs);
151 }
152 
153 
155  const Options& opt, bool local_crs) {
156  F2CField field_c = field.clone();
157  if (!local_crs) {
159  }
161  robot, planCovRoute(robot, field_c.getField(), opt),
162  *getPPTurningBasePtr(opt));
163  return local_crs ? path : f2c::Transform::transformToPrevCRS(path, field_c);
164 }
165 
166 
167 
168 } // namespace f2c
169 
f2c::Options::pp_alg
PPAlg pp_alg
Definition: fields2cover.h:149
f2c::PPAlg::REEDS_SHEPP_HC
@ REEDS_SHEPP_HC
f2c::hg::ConstHL
Class to generate headlands with equal width in each border.
Definition: constant_headland.h:18
f2c::pp::PathPlanning::planPath
static F2CPath planPath(const F2CRobot &robot, const F2CRoute &route, TurningBase &turn)
Compute the coverage path using a route as a reference.
Definition: path_planning.cpp:12
f2c::SGObjFunc::FIELD_COV
@ FIELD_COV
f2c::getSGObjPtr
std::unique_ptr< obj::SGObjective > getSGObjPtr(const Options &opt)
Definition: fields2cover.cpp:36
5_route_planning.swaths
swaths
Definition: 5_route_planning.py:58
f2c::SGObjFunc::N_SWATH_MOD
@ N_SWATH_MOD
1_basic_types.cells
cells
Definition: 1_basic_types.py:93
f2c::SGAlg::BRUTE_FORCE
@ BRUTE_FORCE
f2c::SGObjFunc::SWATH_LENGTH
@ SWATH_LENGTH
f2c::SGObjFunc::OVERLAPS
@ OVERLAPS
2_objective_functions.path
path
Definition: 2_objective_functions.py:88
f2c::types::Field
Definition: Field.h:18
f2c::PPAlg::DUBINS_CC
@ DUBINS_CC
f2c::Options::sg_angle
double sg_angle
Definition: fields2cover.h:145
1_basic_types.cell
cell
Definition: 1_basic_types.py:88
F2CCells
f2c::types::Cells F2CCells
Definition: types.h:44
f2c::Options::sg_alg
SGAlg sg_alg
Definition: fields2cover.h:143
f2c::types::Field::getField
Cells & getField()
Definition: Field.cpp:64
f2c::Options::hg_swaths
int hg_swaths
Definition: fields2cover.h:141
f2c::HGAlg::NONE
@ NONE
2_objective_functions.robot
robot
Definition: 2_objective_functions.py:76
fields2cover.h
f2c::planCovPath
F2CPath planCovPath(const F2CRobot &robot, const F2CCell &cell, const Options &opt=Options())
Definition: fields2cover.cpp:136
5_route_planning.route
route
Definition: 5_route_planning.py:29
3_headland_generator.const_hl
const_hl
Definition: 3_headland_generator.py:17
f2c::planCovRoute
F2CRoute planCovRoute(const F2CRobot &robot, const F2CCell &cell, const Options &opt=Options())
Definition: fields2cover.cpp:81
f2c::Options::sg_obj
SGObjFunc sg_obj
Definition: fields2cover.h:144
f2c::Options
Definition: fields2cover.h:136
f2c::types::Cell
Definition: Cell.h:32
f2c::getPPTurningBasePtr
std::unique_ptr< f2c::pp::TurningBase > getPPTurningBasePtr(const Options &opt)
Definition: fields2cover.cpp:58
f2c::types::Path
Definition: Path.h:23
f2c::PPAlg::DUBINS
@ DUBINS
f2c::rp::RoutePlannerBase::genRoute
virtual F2CRoute genRoute(const F2CCells &cells, const F2CSwathsByCells &swaths_by_cells, bool show_log=false, double d_tol=1e-4, bool redirect_swaths=true, long int time_limit_seconds=1, bool search_for_optimum=false)
Definition: route_planner_base.cpp:21
f2c::SGObjFunc::N_SWATH
@ N_SWATH
f2c::PPAlg::REEDS_SHEPP
@ REEDS_SHEPP
f2c::Options::hg_alg
HGAlg hg_alg
Definition: fields2cover.h:140
f2c::types::Cells
Definition: Cells.h:21
f2c::Transform::transformToPrevCRS
static void transformToPrevCRS(F2CField &field)
Definition: transformation.cpp:197
f2c::types::Route
Definition: Route.h:23
f2c::types::Robot
Definition: Robot.h:25
2_objective_functions.field
field
Definition: 2_objective_functions.py:16
f2c
Main namespace of the fields2cover library.
Definition: boustrophedon_decomp.h:14
f2c::types::SwathsByCells
Definition: SwathsByCells.h:17
f2c::SGAlg::GIVEN_ANGLE
@ GIVEN_ANGLE
f2c::rp::RoutePlannerBase
Definition: route_planner_base.h:23
5_route_planning.bf
bf
Definition: 5_route_planning.py:25
f2c::sg::BruteForce
Definition: brute_force.h:20
f2c::Transform::transformToUTM
static void transformToUTM(F2CField &field, bool is_etrs89_opt=true)
Definition: transformation.cpp:149
f2c::HGAlg::CONST
@ CONST


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