35 #include <Eigen/Eigen>
38 #include <rclcpp/rclcpp.hpp>
51 rclcpp::Time timestamp;
53 std::optional<Eigen::Vector2f> position_xy{
55 std::optional<Eigen::Vector2f> position_xy_variance{
58 std::optional<float> position_z{std::nullopt};
59 std::optional<float> position_z_variance{
62 std::optional<Eigen::Vector3f> velocity{
64 std::optional<Eigen::Vector3f> velocity_variance{
67 std::optional<Eigen::Quaternionf> attitude{
69 std::optional<Eigen::Vector3f> attitude_variance{
72 friend class LocalNavigationInterfaceImpl;
95 const Eigen::Vector3f& position,
const Eigen::Vector3f& position_variance =
105 const Eigen::Vector2f& position_xy,
106 const Eigen::Vector2f& position_xy_variance =
125 const Eigen::Vector3f& velocity,
const Eigen::Vector3f& velocity_variance =
135 const Eigen::Quaternionf& attitude,
136 const Eigen::Vector3f& attitude_variance =
142 class LocalNavigationInterfaceImpl;
161 std::shared_ptr<LocalNavigationInterfaceImpl> _impl;
Interface to inject local position measurements to the flight controller's state estimator.
Definition: local_navigation.hpp:148
void update(const LocalPositionMeasurement &measurement)
Send a local position update to the state estimator.
Local position measurement class with any combination of position (ENU frame), velocity (ENU frame),...
Definition: local_navigation.hpp:49
static constexpr float DEFAULT_ATTITUDE_VARIANCE
Definition: local_navigation.hpp:79
static constexpr float DEFAULT_VELOCITY_VARIANCE
Definition: local_navigation.hpp:77
LocalPositionMeasurement & withPosition(const Eigen::Vector3f &position, const Eigen::Vector3f &position_variance=Eigen::Vector3f::Constant(DEFAULT_POSITION_VARIANCE))
Set the measured position in ENU frame.
static constexpr float DEFAULT_POSITION_VARIANCE
Definition: local_navigation.hpp:75
LocalPositionMeasurement & withVelocity(const Eigen::Vector3f &velocity, const Eigen::Vector3f &velocity_variance=Eigen::Vector3f::Constant(DEFAULT_VELOCITY_VARIANCE))
Set the measured velocity in ENU frame.
LocalPositionMeasurement & withAttitude(const Eigen::Quaternionf &attitude, const Eigen::Vector3f &attitude_variance=Eigen::Vector3f::Constant(DEFAULT_ATTITUDE_VARIANCE))
Set the measured attitude quaternion.
LocalPositionMeasurement & withPositionVertical(const float position_z, const float position_z_variance=DEFAULT_POSITION_VARIANCE)
Set the measured vertical position in ENU frame.
LocalPositionMeasurement & withPositionHorizontal(const Eigen::Vector2f &position_xy, const Eigen::Vector2f &position_xy_variance=Eigen::Vector2f::Constant(DEFAULT_POSITION_VARIANCE))
Set the measured horizontal position in ENU frame.
SDK execution class. All callbacks are called on the same thread.
Definition: auterion.hpp:45