23 #include <Eigen/Eigen>
24 #include <rclcpp/rclcpp.hpp>
25 #include <px4_msgs/msg/vehicle_local_position.hpp>
26 #include <px4_ros2/common/context.hpp>
27 #include <px4_ros2/components/shared_subscription.hpp>
35 class MapProjectionImpl;
66 Eigen::Vector2f
globalToLocal(
const Eigen::Vector2d & global_position)
const;
75 Eigen::Vector3f
globalToLocal(
const Eigen::Vector3d & global_position)
const;
84 Eigen::Vector2d
localToGlobal(
const Eigen::Vector2f & local_position)
const;
93 Eigen::Vector3d
localToGlobal(
const Eigen::Vector3f & local_position)
const;
99 void assertInitalized()
const;
106 void vehicleLocalPositionCallback(
const px4_msgs::msg::VehicleLocalPosition::UniquePtr & msg);
108 rclcpp::Node & _node;
109 std::unique_ptr<MapProjectionImpl> _map_projection_math;
110 SharedSubscriptionCallbackInstance _vehicle_local_position_cb;
123 const Eigen::Vector2d & global_position_now,
124 const Eigen::Vector2d & global_position_next);
136 const Eigen::Vector3d & global_position_now,
137 const Eigen::Vector3d & global_position_next)
140 static_cast<Eigen::Vector2d
>(global_position_now.head(2)),
141 static_cast<Eigen::Vector2d
>(global_position_next.head(2)));
154 const Eigen::Vector3d & global_position_now,
155 const Eigen::Vector3d & global_position_next);
167 const Eigen::Vector2d & global_position_now,
168 const Eigen::Vector2d & global_position_next);
180 const Eigen::Vector3d & global_position_now,
181 const Eigen::Vector3d & global_position_next)
184 static_cast<Eigen::Vector2d
>(global_position_now.head(2)),
185 static_cast<Eigen::Vector2d
>(global_position_next.head(2)));
198 const Eigen::Vector2d & global_position_now,
199 const Eigen::Vector2d & global_position_next);
211 const Eigen::Vector3d & global_position_now,
212 const Eigen::Vector3d & global_position_next)
214 const Eigen::Vector2f vector_res =
216 static_cast<Eigen::Vector2d
>(global_position_now.head(2)),
217 static_cast<Eigen::Vector2d
>(global_position_next.head(2)));
218 const double d_alt = -(global_position_next.z() - global_position_now.z());
219 return Eigen::Vector3f {vector_res.x(), vector_res.y(),
static_cast<float>(d_alt)};
233 const Eigen::Vector2d & global_position_line_start,
234 const Eigen::Vector2d & global_position_line_end,
235 float dist_from_start);
249 const Eigen::Vector2d & global_position_now,
250 float heading,
float dist);
264 const Eigen::Vector3d & global_position_now,
265 float heading,
float dist)
268 static_cast<Eigen::Vector2d
>(global_position_now.head(2)), heading, dist);
269 return Eigen::Vector3d {
270 global_position_res.x(),
271 global_position_res.y(),
272 global_position_now.z()};
285 const Eigen::Vector2d & global_position,
286 const Eigen::Vector2f & vector_ne);
298 const Eigen::Vector3d & global_position,
299 const Eigen::Vector3f & vector_ned)
302 static_cast<Eigen::Vector2d
>(global_position.head(2)),
303 static_cast<Eigen::Vector2f
>(vector_ned.head(2)));
304 const double d_alt = -vector_ned.z();
305 return Eigen::Vector3d {global_position_res.x(), global_position_res.y(),
306 global_position.z() + d_alt};
Definition: context.hpp:20
Provides methods to convert between the geographical coordinate system ("global") and the local azimu...
Definition: geodesic.hpp:48
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 ...
Eigen::Vector2d localToGlobal(const Eigen::Vector2f &local_position) const
Transform a point in the local azimuthal equidistant plane to the geographic coordinate system using ...
Eigen::Vector3d localToGlobal(const Eigen::Vector3f &local_position) 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 ...
static float horizontalDistanceToGlobalPosition(const Eigen::Vector3d &global_position_now, const Eigen::Vector3d &global_position_next)
Compute the horizontal distance between two global positions in meters.
Definition: geodesic.hpp:135
static Eigen::Vector3d globalPositionFromHeadingAndDist(const Eigen::Vector3d &global_position_now, float heading, float dist)
Compute the global position given another global position, distance and heading see http://www....
Definition: geodesic.hpp:263
static float headingToGlobalPosition(const Eigen::Vector3d &global_position_now, const Eigen::Vector3d &global_position_next)
Compute the heading to the next global position in radians.
Definition: geodesic.hpp:179
static Eigen::Vector3d addVectorToGlobalPosition(const Eigen::Vector3d &global_position, const Eigen::Vector3f &vector_ned)
Compute the global position from adding a local frame vector to the current global position.
Definition: geodesic.hpp:297
static Eigen::Vector3f vectorToGlobalPosition(const Eigen::Vector3d &global_position_now, const Eigen::Vector3d &global_position_next)
Compute the vector to the next global position in meters.
Definition: geodesic.hpp:210
float distanceToGlobalPosition(const Eigen::Vector3d &global_position_now, const Eigen::Vector3d &global_position_next)
Compute the distance between two global positions in meters.
Eigen::Vector2d globalPositionFromLineAndDist(const Eigen::Vector2d &global_position_line_start, const Eigen::Vector2d &global_position_line_end, float dist_from_start)
Compute the global position on the line vector defined by two positions (start -> end) at a certain d...