transformation.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 
8 #include <boost/algorithm/string/predicate.hpp>
9 
10 namespace f2c {
11 
12 std::unique_ptr<OGRCoordinateTransformation,
13  void(*)(OGRCoordinateTransformation*)>
15  const std::string& coord_sys_from, const std::string& coord_sys_to) {
16  return createCoordTransf(
17  createSptRef(coord_sys_from), createSptRef(coord_sys_to));
18 }
19 
20 void Transform::transform(F2CField& field, const std::string& coord_sys_to) {
21  if (!field.isEmpty()) {
22  field.setField(field.getField() + field.getRefPoint());
23  field.getField()->transform(
24  generateCoordTransf(field.getCRS(), coord_sys_to).get());
25  field.setRefPoint(field.getField().getCellBorder(0).startPoint());
26  field.setField(field.getField() - field.getRefPoint());
27  } else {
28  field.setRefPoint( \
29  transform(field.getRefPoint(), field.getCRS(), coord_sys_to));
30  }
31  field.setPrevCRS(field.getCRS());
32  field.setCRS(coord_sys_to);
33 }
34 
36  const F2CField& field, const std::string& coord_sys_to) {
37  auto new_route = route.clone();
38  auto coords = generateCoordTransf(field.getCRS(), coord_sys_to);
39  for (size_t i = 0; i < new_route.sizeVectorSwaths(); ++i) {
40  new_route.setSwaths(i, transformSwathsWithFieldRef(
41  new_route.getSwaths(i), field, coord_sys_to));
42  }
43  for (size_t i = 0; i < new_route.sizeConnections(); ++i) {
44  new_route.setConnection(i, transformMultiPointWithFieldRef(
45  new_route.getConnection(i), field, coord_sys_to));
46  }
47  return new_route;
48 }
49 
51  const F2CField& field, const std::string& coord_sys_to) {
52  if (path.size() < 1) {return path;}
53 
54  auto new_path = path;
55  F2CPathState s_end = path.back();
56  if (s_end.len > 0.0) {
57  s_end.point = path.atEnd();
58  s_end.len = 0.0;
59  new_path.addState(s_end);
60  }
61 
62  auto coords = generateCoordTransf(field.getCRS(), coord_sys_to);
63  for (auto&& s : new_path) {
64  s.point = s.point + field.getRefPoint();
65  s.point->transform(coords.get());
66  }
67  for (size_t i = 0; i < new_path.size() - 1; ++i) {
68  new_path[i].len = new_path[i].point.distance(new_path[i+1].point);
69  new_path[i].angle = (new_path[i+1].point - new_path[i].point).getAngleFromPoint();
70  }
71 
72 
73  return new_path;
74 }
75 
77  const F2CField& field, const std::string& coord_sys_to) {
78  F2CMultiPoint new_mp;
79  auto coords = generateCoordTransf(field.getCRS(), coord_sys_to);
80  for (auto&& p : mp) {
81  F2CPoint abs_p = p + field.getRefPoint();
82  abs_p->transform(coords.get());
83  new_mp.addGeometry(abs_p);
84  }
85  return new_mp;
86 }
87 
89  const F2CField& field, const std::string& coord_sys_to) {
90  return F2CSwath(transform(
91  swath.getPath(), field.getRefPoint(), field.getCRS(), coord_sys_to),
92  swath.getWidth(), swath.getId());
93 }
94 
96  const F2CField& field, const std::string& coord_sys_to) {
97  F2CSwaths new_swaths;
98  for (auto&& swath : swaths) {
99  new_swaths.emplace_back(
100  transformSwathWithFieldRef(swath, field, coord_sys_to));
101  }
102  return new_swaths;
103 }
104 
106  const std::string& coord_sys_from, const std::string& coord_sys_to) {
107  F2CStrip new_strip;
108  new_strip.setName(strip.getName());
109  new_strip.setCell(transform(strip.getCell(), coord_sys_from, coord_sys_to));
110  return new_strip;
111 }
112 
114  const std::string& coord_sys_from, const std::string& coord_sys_to) {
115  F2CStrips new_strips;
116  for (auto&& strip : strips) {
117  new_strips.emplace_back(
118  transformStrip(strip, coord_sys_from, coord_sys_to));
119  }
120  return new_strips;
121 }
122 
124  const std::string& coord_sys_from, const std::string& coord_sys_to) {
125  F2CSwaths new_swaths;
126  for (auto&& swath : swaths) {
127  new_swaths.emplace_back(
128  transformSwath(swath, coord_sys_from, coord_sys_to));
129  }
130  return new_swaths;
131 }
132 
134  const std::string& coord_sys_from, const std::string& coord_sys_to) {
135  return F2CSwath(transform(swath.getPath(), coord_sys_from, coord_sys_to),
136  swath.getWidth(), swath.getId());
137 }
138 
140  const std::string& coord_sys_from, const std::string& coord_sys_to) {
141  auto new_path = path;
142  auto coords = generateCoordTransf(coord_sys_from, coord_sys_to);
143  for (auto&& s : new_path) {
144  s.point->transform(coords.get());
145  }
146  return new_path;
147 }
148 
149 void Transform::transformToUTM(F2CField& field, bool is_etrs89_opt) {
150  std::string field_crs = field.getCRS();
151  if (!field_crs.empty() && \
152  field_crs != "EPSG:4258" && field_crs != "EPSG:4326") {
153  transform(field, "EPSG:4326");
154  if (is_etrs89_opt && \
155  (field.getRefPoint().getX() < 32.88 && \
156  field.getRefPoint().getX() > -16.1 && \
157  field.getRefPoint().getY() < 84.73 && \
158  field.getRefPoint().getY() > 40.18) ) {
159  transform(field, "EPSG:4258");
160  }
161  } else if (field_crs.empty()) {
162  if (field.getRefPoint() == F2CPoint(0, 0)) {
163  field = field.clone(); // Move field first point to (0, 0)
164  }
165  if (field.getRefPoint() == F2CPoint(0, 0)) {
166  throw std::out_of_range(
167  "Error on transformToUTM: Coordinates are in a local system");
168  }
169  if (is_etrs89_opt && \
170  (field.getRefPoint().getX() < 32.88 && \
171  field.getRefPoint().getX() > -16.1 && \
172  field.getRefPoint().getY() < 84.73 && \
173  field.getRefPoint().getY() > 40.18) ) {
174  field.setCRS("EPSG:4258");
175  } else if (field.getRefPoint().getX() < 180. && \
176  field.getRefPoint().getX() > -180. && \
177  field.getRefPoint().getY() < 90. && \
178  field.getRefPoint().getY() > -90.) {
179  field.setCRS("EPSG:4326");
180  } else {
181  throw std::invalid_argument(
182  "Error on transformToUTM: Coordinates local system was not recognized");
183  }
184  field_crs = field.getCRS();
185  }
186 
187  std::string utm_zone = std::string("UTM:") + \
188  std::to_string(static_cast<size_t>(
189  floor((field.getRefPoint().getX() + 180) / 6) + 1)) + \
190  (field.getRefPoint().getY() > 0 ? "N" : "S") + \
191  " datum:" + (field.getCRS() == "EPSG:4258" ? "ETRS89" : "WGS84");
192  transform(field, utm_zone);
193  field.setPrevCRS(field_crs);
194 }
195 
196 
198  if (field.getPrevCRS().empty()) {
199  throw std::invalid_argument(
200  "Error in Transform::transformToUTM. No previous CRS recorded.");
201  }
202  transform(field, field.getPrevCRS());
203 }
204 
206  const F2CRoute& route, const F2CField& field) {
207  return transformRouteWithFieldRef(route, field, field.getPrevCRS());
208 }
209 
211  const F2CPath& path, const F2CField& field) {
212  return transformPathWithFieldRef(path, field, field.getPrevCRS());
213 }
214 
216  const F2CStrip& s, const F2CField& field) {
217  return transformStrip(s, field.getCRS(), field.getPrevCRS());
218 }
219 
221  const F2CStrips& s, const F2CField& field) {
222  return transformStrips(s, field.getCRS(), field.getPrevCRS());
223 }
224 
226  const F2CSwath& s, const F2CField& field) {
227  return transformSwathWithFieldRef(s, field, field.getPrevCRS());
228 }
229 
231  const F2CSwaths& s, const F2CField& field) {
232  return transformSwathsWithFieldRef(s, field, field.getPrevCRS());
233 }
234 
236  auto point = field.getRefPoint();
237  point->transform(generateCoordTransf(field.getCRS(), "EPSG:4326").get());
238  return point;
239 }
240 
241 std::unique_ptr<OGRSpatialReference, void(*)(OGRSpatialReference*)>
243  const std::string& coord_sys, bool fail_silently) {
244  auto spt_ref =
245  std::unique_ptr<OGRSpatialReference, void(*)(OGRSpatialReference*)>(
246  new OGRSpatialReference(), [](OGRSpatialReference* ref) {
247  OGRSpatialReference::DestroySpatialReference(ref);});
248  if (coord_sys.empty() && !fail_silently) {
249  throw std::invalid_argument("Coordinate system empty");
250  } else if (F2CField::isCoordSystemEPSG(coord_sys)) {
251  spt_ref->importFromEPSG(F2CField::getEPSGCoordSystem(coord_sys));
252  } else if (F2CField::isCoordSystemUTM(coord_sys)) {
253  std::string proj = (
254  std::string("+proj=utm +zone=") + F2CField::getUTMZone(coord_sys) + " " +
255  F2CField::getUTMHemisphere(coord_sys) +
256  (boost::iequals(F2CField::getUTMDatum(coord_sys), "ETRS89") ?
257  " +ellps=GRS80 +towgs84=0,0,0,0,0,0,0 +type=crs" :
258  " +datum=" + F2CField::getUTMDatum(coord_sys))
259  + " +units=m +no_defs ");
260  spt_ref->importFromProj4(proj.c_str());
261  } else if (!fail_silently) {
262  throw std::invalid_argument("Coordinate system not recognized");
263  }
264  if (GDALVersionInfo("VERSION_NUM")[0] == '3') {
265  // Next line solve issue in https://github.com/OSGeo/gdal/issues/1546
266  spt_ref->SetAxisMappingStrategy(OAMS_TRADITIONAL_GIS_ORDER);
267  }
268  return spt_ref;
269 }
270 
271 
272 std::unique_ptr<OGRCoordinateTransformation,
273  void(*)(OGRCoordinateTransformation*)> Transform::createCoordTransf(
274  std::unique_ptr<OGRSpatialReference, void(*)(OGRSpatialReference*)> in,
275  std::unique_ptr<OGRSpatialReference, void(*)(OGRSpatialReference*)> out) {
276  return std::unique_ptr<OGRCoordinateTransformation,
277  void(*)(OGRCoordinateTransformation*)>(
278  OGRCreateCoordinateTransformation(in.get(), out.get()),
279  [](OGRCoordinateTransformation* coord) {
280  OGRCoordinateTransformation::DestroyCT(coord);});
281 }
282 
283 
284 } // namespace f2c
f2c::types::Swath::getId
int getId() const
Definition: Swath.cpp:151
f2c::types::Swaths::emplace_back
void emplace_back(const Swath &s)
Definition: Swaths.cpp:29
5_route_planning.swaths
swaths
Definition: 5_route_planning.py:58
transformation.h
2_objective_functions.path
path
Definition: 2_objective_functions.py:88
f2c::Transform::createCoordTransf
static std::unique_ptr< OGRCoordinateTransformation, void(*)(OGRCoordinateTransformation *)> createCoordTransf(std::unique_ptr< OGRSpatialReference, void(*)(OGRSpatialReference *)> in, std::unique_ptr< OGRSpatialReference, void(*)(OGRSpatialReference *)> out)
Definition: transformation.cpp:273
f2c::types::Field
Definition: Field.h:18
f2c::Transform::createSptRef
static std::unique_ptr< OGRSpatialReference, void(*)(OGRSpatialReference *)> createSptRef(const std::string &coord_sys, bool fail_silently=false)
Definition: transformation.cpp:242
f2c::types::PathState::point
Point point
Definition: PathState.h:28
f2c::Transform::transformRouteWithFieldRef
static F2CRoute transformRouteWithFieldRef(const F2CRoute &route, const F2CField &field, const std::string &coord_sys_to)
Definition: transformation.cpp:35
f2c::Transform::transform
static void transform(F2CField &field, const std::string &coord_sys_to)
Definition: transformation.cpp:20
f2c::Transform::transformSwathWithFieldRef
static F2CSwath transformSwathWithFieldRef(const F2CSwath &swath, const F2CField &field, const std::string &coord_sys_to)
Definition: transformation.cpp:88
f2c::Transform::transformPathWithFieldRef
static F2CPath transformPathWithFieldRef(const F2CPath &path, const F2CField &field, const std::string &coord_sys_to)
Definition: transformation.cpp:50
f2c::types::Swath::getWidth
double getWidth() const
Definition: Swath.cpp:167
F2CStrips
std::vector< F2CStrip > F2CStrips
Definition: types.h:57
f2c::types::Strip::setCell
void setCell(const Cell &cell)
Definition: Strip.cpp:19
f2c::types::Field::getEPSGCoordSystem
int getEPSGCoordSystem() const
Definition: Field.cpp:139
f2c::types::Swath
Definition: Swath.h:23
f2c::Transform::generateCoordTransf
static std::unique_ptr< OGRCoordinateTransformation, void(*)(OGRCoordinateTransformation *)> generateCoordTransf(const std::string &coord_sys_from, const std::string &coord_sys_to)
Definition: transformation.cpp:14
f2c::types::Strip::getName
std::string getName() const
Definition: Strip.cpp:23
f2c::types::Swath::getPath
LineString getPath() const
Definition: Swath.cpp:159
f2c::types::Strip
Definition: Strip.h:16
f2c::types::PathState
Definition: PathState.h:27
f2c::Transform::transformSwathsWithFieldRef
static F2CSwaths transformSwathsWithFieldRef(const F2CSwaths &swaths, const F2CField &field, const std::string &coord_sys_to)
Definition: transformation.cpp:95
5_route_planning.route
route
Definition: 5_route_planning.py:29
f2c::Transform::transformMultiPointWithFieldRef
static F2CMultiPoint transformMultiPointWithFieldRef(const F2CMultiPoint &mp, const F2CField &field, const std::string &coord_sys_to)
Definition: transformation.cpp:76
f2c::types::Field::isCoordSystemEPSG
bool isCoordSystemEPSG() const
Definition: Field.cpp:130
f2c::Transform::transformStrip
static F2CStrip transformStrip(const F2CStrip &s, const std::string &coord_sys_from, const std::string &coord_sys_to)
Definition: transformation.cpp:105
f2c::Transform::transformSwath
static F2CSwath transformSwath(const F2CSwath &s, const std::string &coord_sys_from, const std::string &coord_sys_to)
Definition: transformation.cpp:133
f2c::types::MultiPoint::addGeometry
void addGeometry(const Point &p)
Definition: MultiPoint.cpp:83
f2c::types::Path
Definition: Path.h:23
f2c::types::MultiPoint
Definition: MultiPoint.h:18
f2c::types::Field::getUTMHemisphere
std::string getUTMHemisphere() const
Definition: Field.cpp:183
f2c::Transform::transformSwaths
static F2CSwaths transformSwaths(const F2CSwaths &s, const std::string &coord_sys_from, const std::string &coord_sys_to)
Definition: transformation.cpp:123
f2c::types::Field::isCoordSystemUTM
bool isCoordSystemUTM() const
Definition: Field.cpp:94
f2c::types::Strip::setName
void setName(const std::string &str)
Definition: Strip.cpp:27
f2c::Transform::transformToPrevCRS
static void transformToPrevCRS(F2CField &field)
Definition: transformation.cpp:197
f2c::types::Route
Definition: Route.h:23
f2c::types::Field::getUTMDatum
std::string getUTMDatum() const
Definition: Field.cpp:122
f2c::types::Point
Definition: Point.h:21
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::Field::getUTMZone
std::string getUTMZone() const
Definition: Field.cpp:168
F2CSwath
f2c::types::Swath F2CSwath
Definition: types.h:50
f2c::types::PathState::len
double len
Definition: PathState.h:30
f2c::types::Strip::getCell
Cell & getCell()
Definition: Strip.cpp:11
f2c::Transform::transformStrips
static F2CStrips transformStrips(const F2CStrips &s, const std::string &coord_sys_from, const std::string &coord_sys_to)
Definition: transformation.cpp:113
f2c::Transform::transformPath
static F2CPath transformPath(const F2CPath &p, const std::string &coord_sys_from, const std::string &coord_sys_to)
Definition: transformation.cpp:139
f2c::types::Swaths
Definition: Swaths.h:20
f2c::Transform::getRefPointInGPS
static F2CPoint getRefPointInGPS(const F2CField &field)
Definition: transformation.cpp:235
f2c::Transform::transformToUTM
static void transformToUTM(F2CField &field, bool is_etrs89_opt=true)
Definition: transformation.cpp:149
f2c::types::to_string
std::string to_string(double d, const int precision=6)
Definition: Path.cpp:274


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