LocalCartesian.cpp
Go to the documentation of this file.
2 
3 #include <GeographicLib/Geocentric.hpp>
4 
5 namespace lanelet {
6 namespace projection {
7 
9  Projector(origin),
10  localCartesian_(origin.position.lat, origin.position.lon, origin.position.ele, GeographicLib::Geocentric::WGS84()) {
11 }
12 
14  BasicPoint3d local{0., 0., 0.};
15  this->localCartesian_.Forward(gps.lat,
16  gps.lon,
17  gps.ele,
18  local[0],
19  local[1],
20  local[2]);
21  return local;
22 }
23 
25  GPSPoint gps{0., 0., 0.};
26  this->localCartesian_.Reverse(local[0],
27  local[1],
28  local[2],
29  gps.lat,
30  gps.lon,
31  gps.ele);
32  return gps;
33 }
34 
35 } // namespace projection
36 } // namespace lanelet
lanelet
lanelet::BasicPoint3d
Eigen::Vector3d BasicPoint3d
LocalCartesian.h
lanelet::Projector
lanelet::projection::LocalCartesianProjector::localCartesian_
GeographicLib::LocalCartesian localCartesian_
Definition: LocalCartesian.h:17
lanelet::projection::LocalCartesianProjector::forward
BasicPoint3d forward(const GPSPoint &gps) const override
Definition: LocalCartesian.cpp:13
lanelet::projection::LocalCartesianProjector::LocalCartesianProjector
LocalCartesianProjector(Origin origin)
Definition: LocalCartesian.cpp:8
lanelet::Origin
lanelet::GPSPoint::lat
double lat
lanelet::GPSPoint::lon
double lon
lanelet::GPSPoint::ele
double ele
lanelet::GPSPoint
lanelet::projection::LocalCartesianProjector::reverse
GPSPoint reverse(const BasicPoint3d &enu) const override
Definition: LocalCartesian.cpp:24


lanelet2_projection
Author(s): Maximilian Naumann , Fabian Poggenhans , Jan-Hendrik Pauls , MichaƂ Antkiewicz
autogenerated on Thu Mar 6 2025 03:26:06