Projection.h
Go to the documentation of this file.
1 #pragma once
3 #include <lanelet2_core/primitives/Point.h>
4 
5 #include <memory>
6 #include <vector>
7 
8 namespace lanelet {
11 struct Origin {
12  explicit Origin(const GPSPoint& position) : position{position}, isDefault{false} {}
13  Origin() = default;
14 
15  static Origin defaultOrigin() { return {}; }
17  bool isDefault{true};
18 };
19 
22 class Projector { // NOLINT
23  public:
24  using Ptr = std::shared_ptr<Projector>;
26  Projector(Projector&& rhs) noexcept = default;
27  Projector& operator=(Projector&& rhs) noexcept = default;
28  Projector(const Projector& rhs) = default;
29  Projector& operator=(const Projector& rhs) = default;
30  virtual ~Projector() noexcept = default;
31 
34  virtual BasicPoint3d forward(const GPSPoint& p) const = 0;
35 
38  virtual GPSPoint reverse(const BasicPoint3d& p) const = 0;
39 
41  const Origin& origin() const { return origin_; }
42 
43  private:
45 };
46 
47 namespace projection {
55  public:
57  BasicPoint3d forward(const GPSPoint& p) const override {
58  const auto scale = std::cos(origin().position.lat * M_PI / 180.0);
59  const double x{scale * p.lon * M_PI * EarthRadius / 180.0};
60  const double y{scale * EarthRadius * std::log(std::tan((90.0 + p.lat) * M_PI / 360.0))};
61  return {x, y, p.ele};
62  }
63 
64  GPSPoint reverse(const BasicPoint3d& p) const override {
65  const double scale = std::cos(origin().position.lat * M_PI / 180.0);
66  const double lon = p.x() * 180.0 / (M_PI * EarthRadius * scale);
67  const double lat = 360.0 * std::atan(std::exp(p.y() / (EarthRadius * scale))) / M_PI - 90.0;
68  return {lat, lon, p.z()};
69  }
70 
71  private:
72  static constexpr double EarthRadius{6378137.0};
73 };
74 } // namespace projection
75 
77 
79 } // namespace lanelet
lanelet
GPSPoint.h
BasicPoint3d
Eigen::Vector3d BasicPoint3d
lanelet::Projector::origin
const Origin & origin() const
Obtain the internal origin.
Definition: Projection.h:41
p
BasicPoint p
lanelet::projection::SphericalMercatorProjector::reverse
GPSPoint reverse(const BasicPoint3d &p) const override
Project a point from local coordinates to global lat/lon coordinates.
Definition: Projection.h:64
lanelet::DefaultProjector
projection::SphericalMercatorProjector DefaultProjector
Definition: Projection.h:76
lanelet::Origin::position
GPSPoint position
Definition: Projection.h:16
lanelet::Origin::Origin
Origin()=default
lanelet::Projector::Ptr
std::shared_ptr< Projector > Ptr
Definition: Projection.h:24
lanelet::Projector
Definition: Projection.h:22
lanelet::Projector::operator=
Projector & operator=(Projector &&rhs) noexcept=default
lanelet::Projector::origin_
Origin origin_
Definition: Projection.h:44
lanelet::Origin
Definition: Projection.h:11
lanelet::Projector::~Projector
virtual ~Projector() noexcept=default
lanelet::projection::SphericalMercatorProjector
implements a simple spherical mercator projection.
Definition: Projection.h:54
lanelet::projection::SphericalMercatorProjector::EarthRadius
static constexpr double EarthRadius
Definition: Projection.h:72
lanelet::projection::SphericalMercatorProjector::forward
BasicPoint3d forward(const GPSPoint &p) const override
Project a point from lat/lon coordinates to a local coordinate system.
Definition: Projection.h:57
lanelet::Projector::Projector
Projector(Origin origin=Origin::defaultOrigin())
Definition: Projection.h:25
lanelet::Projector::forward
virtual BasicPoint3d forward(const GPSPoint &p) const =0
Project a point from lat/lon coordinates to a local coordinate system.
lanelet::defaultProjection
DefaultProjector defaultProjection(Origin origin=Origin::defaultOrigin())
Definition: Projection.h:78
lanelet::Projector::reverse
virtual GPSPoint reverse(const BasicPoint3d &p) const =0
Project a point from local coordinates to global lat/lon coordinates.
lanelet::Origin::Origin
Origin(const GPSPoint &position)
Definition: Projection.h:12
lanelet::Origin::defaultOrigin
static Origin defaultOrigin()
Definition: Projection.h:15
lanelet::Origin::isDefault
bool isDefault
The position of the origin.
Definition: Projection.h:17
lanelet::GPSPoint


lanelet2_io
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:03