Auterion App SDK
Auterion SDK is a library that can be used by AuterionOS apps to communicate with the system.
Loading...
Searching...
No Matches
local_navigation.hpp
1/****************************************************************************
2 *
3 * Copyright 2023 Auterion AG. All rights reserved.
4 *
5 * Redistribution and use in source and binary forms, with or without
6 * modification, are permitted provided that the following conditions are met:
7 *
8 * 1. Redistributions of source code must retain the above copyright notice, this
9 * list of conditions and the following disclaimer.
10 *
11 * 2. Redistributions in binary form must reproduce the above copyright notice,
12 * this list of conditions and the following disclaimer in the documentation
13 * and/or other materials provided with the distribution.
14 *
15 * 3. Neither the name of the copyright holder nor the names of its contributors
16 * may be used to endorse or promote products derived from this software without
17 * specific prior written permission.
18 *
19 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 * POSSIBILITY OF SUCH DAMAGE.
30 *
31 ****************************************************************************/
32
33#pragma once
34
35#include <Eigen/Eigen>
36#include <memory>
37#include <optional>
38#include <rclcpp/rclcpp.hpp>
39
40namespace auterion {
50 private:
51 rclcpp::Time timestamp;
53 std::optional<Eigen::Vector2f> position_xy{
54 std::nullopt};
55 std::optional<Eigen::Vector2f> position_xy_variance{
56 std::nullopt};
58 std::optional<float> position_z{std::nullopt};
59 std::optional<float> position_z_variance{
60 std::nullopt};
62 std::optional<Eigen::Vector3f> velocity{
63 std::nullopt};
64 std::optional<Eigen::Vector3f> velocity_variance{
65 std::nullopt};
67 std::optional<Eigen::Quaternionf> attitude{
68 std::nullopt};
69 std::optional<Eigen::Vector3f> attitude_variance{
70 std::nullopt};
72 friend class LocalNavigationInterfaceImpl;
73
74 public:
75 static constexpr float DEFAULT_POSITION_VARIANCE =
76 0.01;
77 static constexpr float DEFAULT_VELOCITY_VARIANCE =
78 0.01;
79 static constexpr float DEFAULT_ATTITUDE_VARIANCE =
80 0.01;
82 LocalPositionMeasurement(const rclcpp::Time& measurement_time);
83
85
86 ~LocalPositionMeasurement() = default;
87
95 const Eigen::Vector3f& position, const Eigen::Vector3f& position_variance =
96 Eigen::Vector3f::Constant(DEFAULT_POSITION_VARIANCE));
97
105 const Eigen::Vector2f& position_xy,
106 const Eigen::Vector2f& position_xy_variance =
107 Eigen::Vector2f::Constant(DEFAULT_POSITION_VARIANCE));
108
116 const float position_z, const float position_z_variance = DEFAULT_POSITION_VARIANCE);
117
125 const Eigen::Vector3f& velocity, const Eigen::Vector3f& velocity_variance =
126 Eigen::Vector3f::Constant(DEFAULT_VELOCITY_VARIANCE));
127
135 const Eigen::Quaternionf& attitude,
136 const Eigen::Vector3f& attitude_variance =
137 Eigen::Vector3f::Constant(DEFAULT_ATTITUDE_VARIANCE));
138};
139
140class SDK;
141
142class LocalNavigationInterfaceImpl;
143
149 public:
151
152 ~LocalNavigationInterface() = default;
153
158 void update(const LocalPositionMeasurement& measurement);
159
160 private:
161 std::shared_ptr<LocalNavigationInterfaceImpl> _impl;
162};
163
165} // namespace auterion
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
LocalPositionMeasurement & withVelocity(const Eigen::Vector3f &velocity, const Eigen::Vector3f &velocity_variance=Eigen::Vector3f::Constant(DEFAULT_VELOCITY_VARIANCE))
Set the measured velocity in ENU frame.
static constexpr float DEFAULT_VELOCITY_VARIANCE
Definition local_navigation.hpp:77
LocalPositionMeasurement & withPositionVertical(const float position_z, const float position_z_variance=DEFAULT_POSITION_VARIANCE)
Set the measured vertical position in ENU frame.
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 & withAttitude(const Eigen::Quaternionf &attitude, const Eigen::Vector3f &attitude_variance=Eigen::Vector3f::Constant(DEFAULT_ATTITUDE_VARIANCE))
Set the measured attitude quaternion.
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:97