35 #include <Eigen/Eigen>
36 #include <auterion_sdk/auterion.hpp>
44 class MapProjectionImpl;
72 Eigen::Vector2f
globalToLocal(
const Eigen::Vector2d& global_position)
const;
81 Eigen::Vector3f
globalToLocal(
const Eigen::Vector3d& global_position)
const;
90 Eigen::Vector2d
localToGlobal(
const Eigen::Vector2f& local_position_en)
const;
99 Eigen::Vector3d
localToGlobal(
const Eigen::Vector3f& local_position_enu)
const;
102 std::unique_ptr<MapProjectionImpl> _impl;
112 float horizontalDistanceToGlobalPosition(
const Eigen::Vector2d& global_position_now,
113 const Eigen::Vector2d& global_position_next);
122 float horizontalDistanceToGlobalPosition(
const Eigen::Vector3d& global_position_now,
123 const Eigen::Vector3d& global_position_next);
132 float distanceToGlobalPosition(
const Eigen::Vector3d& global_position_now,
133 const Eigen::Vector3d& global_position_next);
142 float headingToGlobalPosition(
const Eigen::Vector2d& global_position_now,
143 const Eigen::Vector2d& global_position_next);
152 float headingToGlobalPosition(
const Eigen::Vector3d& global_position_now,
153 const Eigen::Vector3d& global_position_next);
162 Eigen::Vector2f vectorToGlobalPosition(
const Eigen::Vector2d& global_position_now,
163 const Eigen::Vector2d& global_position_next);
172 Eigen::Vector3f vectorToGlobalPosition(
const Eigen::Vector3d& global_position_now,
173 const Eigen::Vector3d& global_position_next);
184 Eigen::Vector2d globalPositionFromLineAndDist(
const Eigen::Vector2d& global_position_line_start,
185 const Eigen::Vector2d& global_position_line_end,
186 float dist_from_start);
197 Eigen::Vector2d globalPositionFromHeadingAndDist(
const Eigen::Vector2d& global_position_now,
198 float heading,
float dist);
209 Eigen::Vector3d globalPositionFromHeadingAndDist(
const Eigen::Vector3d& global_position_now,
210 float heading,
float dist);
220 Eigen::Vector2d addVectorToGlobalPosition(
const Eigen::Vector2d& global_position,
221 const Eigen::Vector2f& vector_enu);
231 Eigen::Vector3d addVectorToGlobalPosition(
const Eigen::Vector3d& global_position,
232 const Eigen::Vector3f& vector_enu);
Provides methods to convert between the geographical coordinate system ("global") and the ENU local a...
Definition: geodesic.hpp:54
Eigen::Vector2d localToGlobal(const Eigen::Vector2f &local_position_en) const
Transform a point in the local azimuthal equidistant plane to the geographic coordinate system using ...
Eigen::Vector3f globalToLocal(const Eigen::Vector3d &global_position) const
Transform a point in the geographic coordinate system to the local azimuthal equidistant plane using ...
Eigen::Vector3d localToGlobal(const Eigen::Vector3f &local_position_enu) const
Transform a point in the local azimuthal equidistant plane to the geographic coordinate system using ...
bool isInitialized() const
Eigen::Vector2f globalToLocal(const Eigen::Vector2d &global_position) const
Transform a point in the geographic coordinate system to the local azimuthal equidistant plane using ...
SDK execution class. All callbacks are called on the same thread.
Definition: auterion.hpp:45