• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

Fields2Cover / Fields2Cover / 20856591435

09 Jan 2026 03:22PM UTC coverage: 84.057% (-1.7%) from 85.73%
20856591435

push

github

web-flow
Fix docs (#215)

* Ignore google test templates in the docs

* Include gtest_main

* Exclude symlinks

* Exclude googletest from documentation

1274 of 1519 branches covered (83.87%)

2362 of 2810 relevant lines covered (84.06%)

8860.72 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

90.15
/src/fields2cover/route_planning/route_planner_base.cpp
1
//=============================================================================
2
//    Copyright (C) 2021-2024 Wageningen University - All Rights Reserved
3
//                     Author: Gonzalo Mier
4
//                        BSD-3 License
5
//=============================================================================
6

7
#include <ortools/constraint_solver/routing.h>
8
#include <ortools/constraint_solver/routing_enums.pb.h>
9
#include <ortools/constraint_solver/routing_index_manager.h>
10
#include <ortools/constraint_solver/routing_parameters.h>
11
#include <math.h>
12
#include <utility>
13
#include <vector>
14
#include <limits>
15
#include "fields2cover/route_planning/route_planner_base.h"
16

17
namespace f2c::rp {
18

19
namespace ortools = operations_research;
20

21
F2CRoute RoutePlannerBase::genRoute(
22
    const F2CCells& cells, const F2CSwathsByCells& swaths,
23
    bool show_log, double d_tol, bool redirect_swaths,
24
    long int time_limit_seconds, bool search_for_optimum) {
25
  F2CGraph2D shortest_graph = createShortestGraph(cells, swaths, d_tol);
3✔
26

27
  F2CGraph2D cov_graph = createCoverageGraph(
3✔
28
      cells, swaths, shortest_graph, d_tol, redirect_swaths);
3✔
29

30
  std::vector<long long int> v_route = computeBestRoute(
3✔
31
      cov_graph, show_log, time_limit_seconds, search_for_optimum);
3✔
32
  return transformSolutionToRoute(
3✔
33
      v_route, swaths, cov_graph, shortest_graph);
6✔
34
}
3✔
35

36
void RoutePlannerBase::setStartAndEndPoint(const F2CPoint& p) {
37
  this->r_start_end = p;
×
38
}
×
39

40
F2CGraph2D RoutePlannerBase::createShortestGraph(
41
    const F2CCells& cells, const F2CSwathsByCells& swaths_by_cells,
42
    double d_tol) const {
43
  F2CGraph2D g;
3✔
44
  // Add points from swaths that touches border
45
  for (auto&& swaths : swaths_by_cells) {
19✔
46
    for (auto&& s : swaths) {
62✔
47
      g.addEdge(s.startPoint(), cells.closestPointOnBorderTo(s.startPoint()));
46✔
48
      g.addEdge(s.endPoint(),   cells.closestPointOnBorderTo(s.endPoint()));
46✔
49
    }
50
  }
51

52
  // Add points in the border
53
  for (auto&& cell : cells) {
6✔
54
    for (auto&& ring : cell) {
10✔
55
      for (size_t i = 0; i < ring.size()-1; ++i) {
39✔
56
        g.addEdge(ring.getGeometry(i), ring.getGeometry(i+1));
32✔
57
      }
58
    }
3✔
59
  }
3✔
60

61
  // Add start and end point if they exists
62
  if (this->r_start_end) {
3✔
63
    g.addEdge(*r_start_end, cells.closestPointOnBorderTo(*r_start_end));
×
64
  }
65

66
  std::vector<F2CPoint> nodes = g.getNodes();
3✔
67

68
  // Connect nodes that are near other edges.
69
  for (int i = 0; i < 2; ++i) {
9✔
70
    auto edges = g.getEdges();
6✔
71
    for (auto&& edge : edges) {
422✔
72
      size_t from = edge.first;
416✔
73
      for (auto&& e : edge.second) {
1,216✔
74
        size_t to = e.first;
800✔
75

76
        F2CLineString border {g.indexToNode(from), g.indexToNode(to)};
2,400✔
77
        for (auto&& n : nodes) {
56,752✔
78
          if (n != border[0] && n != border[1] && n.distance(border) < d_tol) {
55,952✔
79
            g.addEdge(border[0], n);
1,208✔
80
            g.addEdge(n, border[1]);
1,208✔
81
            g.removeEdge(border[0], border[1]);
1,208✔
82
          }
83
        }
84
      }
800✔
85
    }
86
  }
6✔
87
  return g;
6✔
88
}
803✔
89

90

91
F2CGraph2D RoutePlannerBase::createCoverageGraph(
92
    const F2CCells& cells, const F2CSwathsByCells& swaths_by_cells,
93
    F2CGraph2D& shortest_graph,
94
    double d_tol, bool redirect_swaths) const {
95
  F2CGraph2D g;
3✔
96
  for (auto&& swaths : swaths_by_cells) {
19✔
97
    for (auto&& s : swaths) {
62✔
98
      F2CPoint mid_p {(s.startPoint() + s.endPoint()) * 0.5};
46✔
99
      if (redirect_swaths) {
46✔
100
        g.addEdge(s.startPoint(), mid_p, 0);
30✔
101
        g.addEdge(s.endPoint(), mid_p, 0);
30✔
102
      } else {
103
        g.addDirectedEdge(s.startPoint(), mid_p, 0);
16✔
104
        g.addDirectedEdge(mid_p, s.endPoint(), 0);
16✔
105
      }
106
    }
46✔
107
  }
108

109
  for (const auto& swaths1 : swaths_by_cells) {
19✔
110
    for (const auto& s1 : swaths1) {
62✔
111
      auto s1_s = s1.startPoint();
46✔
112
      auto s1_e = s1.endPoint();
46✔
113
      for (const auto& swaths2 : swaths_by_cells) {
298✔
114
        for (const auto& s2 : swaths2) {
960✔
115
          auto s2_s = s2.startPoint();
708✔
116
          auto s2_e = s2.endPoint();
708✔
117
          if (redirect_swaths) {
708✔
118
            g.addEdge(s1_s, s2_s, shortest_graph);
452✔
119
            g.addEdge(s1_e, s2_e, shortest_graph);
452✔
120
            g.addEdge(s1_s, s2_e, shortest_graph);
452✔
121
            g.addEdge(s1_e, s2_s, shortest_graph);
452✔
122
          } else {
123
            g.addDirectedEdge(s1_e, s2_s, shortest_graph);
256✔
124
          }
125
        }
708✔
126
      }
127
    }
46✔
128
  }
129

130
  F2CPoint deposit(-1e8, -1e8);  // Arbitrary point
3✔
131
  if (this->r_start_end) {
3✔
132
    deposit = *this->r_start_end;
×
133
  }
134

135
  for (auto&& swaths : swaths_by_cells) {
19✔
136
    for (auto&& s : swaths) {
62✔
137
      if (this->r_start_end) {
46✔
138
        g.addEdge(s.startPoint(), deposit, shortest_graph);
×
139
        g.addEdge(s.endPoint(), deposit, shortest_graph);
×
140
      } else {
141
        g.addEdge(s.startPoint(), deposit, 0);
46✔
142
        g.addEdge(s.endPoint(), deposit, 0);
46✔
143
      }
144
    }
145
  }
146
  return g;
6✔
147
}
3✔
148

149
std::vector<long long int> RoutePlannerBase::computeBestRoute(
150
    const F2CGraph2D& cov_graph, bool show_log, long int time_limit_seconds,
151
    bool use_guided_local_search) const {
152
  int depot_id = static_cast<int>(cov_graph.numNodes()-1);
3✔
153
  const ortools::RoutingIndexManager::NodeIndex depot{depot_id};
3✔
154
  ortools::RoutingIndexManager manager(cov_graph.numNodes(), 1, depot);
3✔
155
  ortools::RoutingModel routing(manager);
3✔
156

157
  const int transit_callback_index = routing.RegisterTransitCallback(
3✔
158
      [&cov_graph, &manager] (long long int from, long long int to) -> long long int {
159
        auto from_node = manager.IndexToNode(from).value();
126,258✔
160
        auto to_node = manager.IndexToNode(to).value();
126,258✔
161
        return cov_graph.getCostFromEdge(from_node, to_node);
126,258✔
162
      });
163
  routing.SetArcCostEvaluatorOfAllVehicles(transit_callback_index);
3✔
164
  ortools::RoutingSearchParameters searchParameters =
165
    ortools::DefaultRoutingSearchParameters();
3✔
166
  searchParameters.set_use_full_propagation(false);
3✔
167
  searchParameters.set_first_solution_strategy(
3✔
168
    ortools::FirstSolutionStrategy::AUTOMATIC);
169
  if (use_guided_local_search) {
3✔
170
    searchParameters.set_local_search_metaheuristic(
×
171
      ortools::LocalSearchMetaheuristic::GUIDED_LOCAL_SEARCH);
172
  } else {
173
    searchParameters.set_local_search_metaheuristic(
3✔
174
      ortools::LocalSearchMetaheuristic::AUTOMATIC);
175
  }
176
  searchParameters.mutable_time_limit()->set_seconds(time_limit_seconds);
3✔
177
  searchParameters.set_log_search(show_log);
3✔
178
  const ortools::Assignment* solution =
179
    routing.SolveWithParameters(searchParameters);
3✔
180

181
  long long int index = routing.Start(0);
3✔
182
  std::vector<long long int> v_id;
3✔
183

184
  index = solution->Value(routing.NextVar(index));
3✔
185

186
  while (!routing.IsEnd(index)) {
141✔
187
    v_id.emplace_back(manager.IndexToNode(index).value());
138✔
188
    index = solution->Value(routing.NextVar(index));
138✔
189
  }
190
  return v_id;
6✔
191
}
3✔
192

193
F2CRoute RoutePlannerBase::transformSolutionToRoute(
194
    const std::vector<long long int>& route_ids,
195
    const F2CSwathsByCells& swaths_by_cells,
196
    const F2CGraph2D& coverage_graph,
197
    F2CGraph2D& shortest_graph) const {
198
  F2CRoute route;
3✔
199
  F2CSwath swath;
3✔
200
  const size_t NS = swaths_by_cells.sizeTotal();
3✔
201
  for (int i = 0; i < route_ids.size()-2; ++i) {
135✔
202
    F2CPoint p_s = coverage_graph.indexToNode(route_ids[i]);
132✔
203
    F2CPoint p_e = coverage_graph.indexToNode(route_ids[i+2]);
132✔
204
    for (int j = 0; j < NS; ++j) {
1,787✔
205
      F2CSwath swath = swaths_by_cells.getSwath(j).clone();
1,701✔
206
      if (p_s == swath.startPoint() && p_e == swath.endPoint()) {
1,701✔
207
        if (route.isEmpty() && r_start_end) {
31✔
208
          route.addConnection(shortest_graph.shortestPath(
×
209
                *r_start_end, swath.startPoint()));
×
210
        }
211
        route.addSwath(swath, shortest_graph);
31✔
212
        break;
31✔
213
      } else if (p_e == swath.startPoint() && p_s == swath.endPoint()) {
1,670✔
214
        swath.reverse();
15✔
215
        if (route.isEmpty() && r_start_end) {
15✔
216
          route.addConnection(shortest_graph.shortestPath(
×
217
                *r_start_end, swath.startPoint()));
×
218
        }
219
        route.addSwath(swath, shortest_graph);
15✔
220
        break;
15✔
221
      }
222
    }
1,701✔
223
  }
132✔
224
  if (r_start_end) {
3✔
225
    route.addConnection(shortest_graph.shortestPath(
×
226
          route.endPoint(), *r_start_end));
×
227
  }
228
  return route;
6✔
229
}
3✔
230

231
}  // namespace f2c::rp
232

233

STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc