37 #include <rclcpp/rclcpp.hpp>
50 rclcpp::Time timestamp;
52 std::optional<double> latitude_deg{std::nullopt};
53 std::optional<double> longitude_deg{std::nullopt};
54 std::optional<float> horizontal_variance_m2{
57 std::optional<float> altitude_amsl_m{
59 std::optional<float> vertical_variance_m2{
62 friend class GlobalNavigationInterfaceImpl;
82 const double latitude,
const double longitude,
97 class GlobalNavigationInterfaceImpl;
125 std::shared_ptr<GlobalNavigationInterfaceImpl> _impl;
Interface to inject global position measurements to the flight controller's state estimator.
Definition: global_navigation.hpp:103
void reset_horizontal_position()
Notify the FMU that the global position estimate for horizontal position (latitude and longitude) has...
void update(const GlobalPositionMeasurement &measurement)
Send a global position update to the state estimator.
Global position measurement class with a horizontal position (latitude and longitude),...
Definition: global_navigation.hpp:48
static constexpr float DEFAULT_POSITION_VARIANCE
Definition: global_navigation.hpp:66
GlobalPositionMeasurement & withPosition(const double latitude, const double longitude, const float horizontal_variance=DEFAULT_POSITION_VARIANCE)
Set the measured horizontal position.
GlobalPositionMeasurement & withAltitude(const float altitude_amsl, const float vertical_variance=DEFAULT_POSITION_VARIANCE)
Set the measured altitude.
SDK execution class. All callbacks are called on the same thread.
Definition: auterion.hpp:45