18#include "Navigation/Transformations/Units.hpp"
29 [[nodiscard]]
static std::string
type()
36 [[nodiscard]] std::string
getType()
const override {
return type(); }
52 desc.emplace_back(
"Roll [deg]");
53 desc.emplace_back(
"Pitch [deg]");
54 desc.emplace_back(
"Yaw [deg]");
55 desc.emplace_back(
"Quaternion::w");
56 desc.emplace_back(
"Quaternion::x");
57 desc.emplace_back(
"Quaternion::y");
58 desc.emplace_back(
"Quaternion::z");
74 [[nodiscard]] std::optional<double>
getValueAt(
size_t idx)
const override
111 [[nodiscard]]
bool setValueAt(
size_t idx,
double value)
override
136 [[nodiscard]]
const Eigen::Quaterniond&
n_Quat_b()
const
150 [[nodiscard]]
const Eigen::Quaterniond&
e_Quat_b()
const
166 return trafo::quat2eulerZYX(
n_Quat_b());
175 template<
typename Derived>
184 template<
typename Derived>
195 template<
typename DerivedP,
typename DerivedV,
typename DerivedA>
207 template<
typename DerivedP,
typename DerivedV,
typename DerivedA>
221 template<
typename DerivedP,
typename DerivedP2,
typename DerivedV,
typename DerivedV2,
typename DerivedA>
223 const Eigen::MatrixBase<DerivedV>&
e_velocity,
const Eigen::MatrixBase<DerivedV2>& e_velocityCovarianceMatrix,
224 const Eigen::QuaternionBase<DerivedA>&
e_Quat_b)
237 template<
typename DerivedP,
typename DerivedP2,
typename DerivedV,
typename DerivedV2,
typename DerivedA>
239 const Eigen::MatrixBase<DerivedV>&
n_velocity,
const Eigen::MatrixBase<DerivedV2>& n_velocityCovarianceMatrix,
240 const Eigen::QuaternionBase<DerivedA>&
n_Quat_b)
#define INS_ASSERT(_EXPR)
Assert function wrapper.
Definition Assert.h:19
Transformation collection.
Position, Velocity and Attitude Storage Class.
Position, Velocity and Attitude Storage Class.
Definition PosVelAtt.hpp:25
Eigen::Quaterniond b_Quat_n() const
Returns the Quaternion from navigation to body frame (NED)
Definition PosVelAtt.hpp:143
size_t staticDescriptorCount() const override
Get the amount of descriptors.
Definition PosVelAtt.hpp:69
void setStateAndStdDev_e(const Eigen::MatrixBase< DerivedP > &e_position, const Eigen::MatrixBase< DerivedP2 > &e_positionCovarianceMatrix, const Eigen::MatrixBase< DerivedV > &e_velocity, const Eigen::MatrixBase< DerivedV2 > &e_velocityCovarianceMatrix, const Eigen::QuaternionBase< DerivedA > &e_Quat_b)
Set the State and the standard deviations.
Definition PosVelAtt.hpp:222
std::vector< std::string > staticDataDescriptors() const override
Returns a vector of data descriptors.
Definition PosVelAtt.hpp:66
void setAttitude_e_Quat_b(const Eigen::QuaternionBase< Derived > &e_Quat_b)
Set the Quaternion from body to earth frame.
Definition PosVelAtt.hpp:176
void setState_n(const Eigen::MatrixBase< DerivedP > &lla_position, const Eigen::MatrixBase< DerivedV > &n_velocity, const Eigen::QuaternionBase< DerivedA > &n_Quat_b)
Set the State.
Definition PosVelAtt.hpp:208
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition PosVelAtt.hpp:48
static constexpr size_t GetStaticDescriptorCount()
Get the amount of descriptors.
Definition PosVelAtt.hpp:63
std::optional< double > getValueAt(size_t idx) const override
Get the value at the index.
Definition PosVelAtt.hpp:74
Eigen::Quaterniond _n_Quat_b
Quaternion body to navigation frame (roll, pitch, yaw)
Definition PosVelAtt.hpp:255
void setAttitude_n_Quat_b(const Eigen::QuaternionBase< Derived > &n_Quat_b)
Set the Quaternion from body to navigation frame.
Definition PosVelAtt.hpp:185
const Eigen::Quaterniond & n_Quat_b() const
Returns the Quaternion from body to navigation frame (NED)
Definition PosVelAtt.hpp:136
bool setValueAt(size_t idx, double value) override
Set the value at the index.
Definition PosVelAtt.hpp:111
static std::string type()
Returns the type of the data class.
Definition PosVelAtt.hpp:29
void setState_e(const Eigen::MatrixBase< DerivedP > &e_position, const Eigen::MatrixBase< DerivedV > &e_velocity, const Eigen::QuaternionBase< DerivedA > &e_Quat_b)
Set the State.
Definition PosVelAtt.hpp:196
void setStateAndStdDev_n(const Eigen::MatrixBase< DerivedP > &lla_position, const Eigen::MatrixBase< DerivedP2 > &n_positionCovarianceMatrix, const Eigen::MatrixBase< DerivedV > &n_velocity, const Eigen::MatrixBase< DerivedV2 > &n_velocityCovarianceMatrix, const Eigen::QuaternionBase< DerivedA > &n_Quat_b)
Set the State and the standard deviations.
Definition PosVelAtt.hpp:238
Eigen::Quaterniond b_Quat_e() const
Returns the Quaternion from Earth-fixed to body frame.
Definition PosVelAtt.hpp:157
Eigen::Quaterniond _e_Quat_b
Quaternion body to earth frame.
Definition PosVelAtt.hpp:253
Eigen::Vector3d rollPitchYaw() const
Returns the Roll, Pitch and Yaw angles in [rad].
Definition PosVelAtt.hpp:164
std::string getType() const override
Returns the type of the data class.
Definition PosVelAtt.hpp:36
const Eigen::Quaterniond & e_Quat_b() const
Returns the Quaternion from body to Earth-fixed frame.
Definition PosVelAtt.hpp:150
static std::vector< std::string > parentTypes()
Returns the parent types of the data class.
Definition PosVelAtt.hpp:40
Position, Velocity and Attitude Storage Class.
Definition PosVel.hpp:23
static constexpr size_t GetStaticDescriptorCount()
Get the amount of descriptors.
Definition PosVel.hpp:73
static std::vector< std::string > parentTypes()
Returns the parent types of the data class.
Definition PosVel.hpp:38
const Eigen::Vector3d & n_velocity() const
Returns the velocity in [m/s], in navigation coordinates.
Definition PosVel.hpp:237
bool setValueAt(size_t idx, double value) override
Set the value at the index.
Definition PosVel.hpp:150
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition PosVel.hpp:46
static std::string type()
Returns the type of the data class.
Definition PosVel.hpp:27
void setVelocityAndStdDev_n(const Eigen::MatrixBase< Derived > &n_velocity, const Eigen::MatrixBase< Derived2 > &n_velocityCovarianceMatrix)
Set the Velocity in NED coordinates and its standard deviation.
Definition PosVel.hpp:288
const Eigen::Vector3d & e_velocity() const
Returns the velocity in [m/s], in earth coordinates.
Definition PosVel.hpp:234
std::optional< double > getValueAt(size_t idx) const override
Get the value at the index.
Definition PosVel.hpp:84
void setVelocityAndStdDev_e(const Eigen::MatrixBase< Derived > &e_velocity, const Eigen::MatrixBase< Derived2 > &e_velocityCovarianceMatrix)
Set the Velocity in ECEF coordinates and its standard deviation.
Definition PosVel.hpp:277
void setVelocity_n(const Eigen::MatrixBase< Derived > &n_velocity)
Set the Velocity in the NED frame.
Definition PosVel.hpp:267
void setVelocity_e(const Eigen::MatrixBase< Derived > &e_velocity)
Set the Velocity in the earth frame.
Definition PosVel.hpp:258
void setPositionAndStdDev_e(const Eigen::MatrixBase< Derived > &e_position, const Eigen::MatrixBase< Derived2 > &e_positionCovarianceMatrix)
Set the Position in ECEF coordinates and its standard deviation.
Definition Pos.hpp:305
Eigen::Quaterniond e_Quat_n() const
Returns the Quaternion from navigation to Earth-fixed frame.
Definition Pos.hpp:218
Eigen::Quaterniond n_Quat_e() const
Returns the Quaternion from Earth-fixed frame to navigation.
Definition Pos.hpp:225
const Eigen::Vector3d & e_position() const
Returns the coordinates in [m].
Definition Pos.hpp:265
void setPositionAndStdDev_lla(const Eigen::MatrixBase< Derived > &lla_position, const Eigen::MatrixBase< Derived2 > &n_positionCovarianceMatrix)
Set the Position in LLA coordinates and its standard deviation.
Definition Pos.hpp:316
void setPosition_e(const Eigen::MatrixBase< Derived > &e_position)
Set the Position in coordinates.
Definition Pos.hpp:286
const Eigen::Vector3d & lla_position() const
Returns the latitude 𝜙, longitude λ and altitude (height above ground) in [rad, rad,...
Definition Pos.hpp:253
void setPosition_lla(const Eigen::MatrixBase< Derived > &lla_position)
Set the Position lla object.
Definition Pos.hpp:295