18#include "Navigation/Transformations/Units.hpp"
29 [[nodiscard]]
static std::string
type()
48 desc.emplace_back(
"Roll [deg]");
49 desc.emplace_back(
"Pitch [deg]");
50 desc.emplace_back(
"Yaw [deg]");
51 desc.emplace_back(
"Quaternion::w");
52 desc.emplace_back(
"Quaternion::x");
53 desc.emplace_back(
"Quaternion::y");
54 desc.emplace_back(
"Quaternion::z");
70 [[nodiscard]] std::optional<double>
getValueAt(
size_t idx)
const override
141 [[nodiscard]]
const Eigen::Quaterniond&
n_Quat_b()
const
155 [[nodiscard]]
const Eigen::Quaterniond&
e_Quat_b()
const
171 return trafo::quat2eulerZYX(
n_Quat_b());
223 const Eigen::Vector3d&
e_velocity,
const Eigen::Matrix3d& e_velocityCovarianceMatrix,
238 const Eigen::Vector3d&
n_velocity,
const Eigen::Matrix3d& n_velocityCovarianceMatrix,
252 Eigen::Quaterniond _e_Quat_b{ 0, 0, 0, 0 };
254 Eigen::Quaterniond _n_Quat_b{ 0, 0, 0, 0 };
#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:148
void setStateAndCovariance_n(const Eigen::Vector3d &lla_position, const Eigen::Matrix3d &n_positionCovarianceMatrix, const Eigen::Vector3d &n_velocity, const Eigen::Matrix3d &n_velocityCovarianceMatrix, const Eigen::Quaterniond &n_Quat_b)
Set the State and the covariances.
Definition PosVelAtt.hpp:237
size_t staticDescriptorCount() const override
Get the amount of descriptors.
Definition PosVelAtt.hpp:65
void setStateAndCovariance_e(const Eigen::Vector3d &e_position, const Eigen::Matrix3d &e_positionCovarianceMatrix, const Eigen::Vector3d &e_velocity, const Eigen::Matrix3d &e_velocityCovarianceMatrix, const Eigen::Quaterniond &e_Quat_b)
Set the State and the covariances.
Definition PosVelAtt.hpp:222
std::vector< std::string > staticDataDescriptors() const override
Returns a vector of data descriptors.
Definition PosVelAtt.hpp:62
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition PosVelAtt.hpp:44
void setAttitude_n_Quat_b(const Eigen::Quaterniond &n_Quat_b)
Set the Quaternion from body to navigation frame.
Definition PosVelAtt.hpp:188
static constexpr size_t GetStaticDescriptorCount()
Get the amount of descriptors.
Definition PosVelAtt.hpp:59
std::optional< double > getValueAt(size_t idx) const override
Get the value at the index.
Definition PosVelAtt.hpp:70
void setState_e(const Eigen::Vector3d &e_position, const Eigen::Vector3d &e_velocity, const Eigen::Quaterniond &e_Quat_b)
Set the State.
Definition PosVelAtt.hpp:198
const Eigen::Quaterniond & n_Quat_b() const
Returns the Quaternion from body to navigation frame (NED)
Definition PosVelAtt.hpp:141
static std::string type()
Returns the type of the data class.
Definition PosVelAtt.hpp:29
void setAttitude_e_Quat_b(const Eigen::Quaterniond &e_Quat_b)
Set the Quaternion from body to earth frame.
Definition PosVelAtt.hpp:180
Eigen::Quaterniond b_Quat_e() const
Returns the Quaternion from Earth-fixed to body frame.
Definition PosVelAtt.hpp:162
void setState_n(const Eigen::Vector3d &lla_position, const Eigen::Vector3d &n_velocity, const Eigen::Quaterniond &n_Quat_b)
Set the State.
Definition PosVelAtt.hpp:209
Eigen::Vector3d rollPitchYaw() const
Returns the Roll, Pitch and Yaw angles in [rad].
Definition PosVelAtt.hpp:169
const Eigen::Quaterniond & e_Quat_b() const
Returns the Quaternion from body to Earth-fixed frame.
Definition PosVelAtt.hpp:155
static std::vector< std::string > parentTypes()
Returns the parent types of the data class.
Definition PosVelAtt.hpp:36
Position, Velocity and Attitude Storage Class.
Definition PosVel.hpp:23
static std::vector< std::string > parentTypes()
Returns the parent types of the data class.
Definition PosVel.hpp:34
void setVelocityAndStdDev_e(const Eigen::Vector3d &e_velocity, const Eigen::Matrix3d &e_velocityCovarianceMatrix)
Set the Velocity in ECEF coordinates and its standard deviation.
Definition PosVel.hpp:233
const Eigen::Vector3d & n_velocity() const
Returns the velocity in [m/s], in navigation coordinates.
Definition PosVel.hpp:196
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition PosVel.hpp:42
void setVelocity_e(const Eigen::Vector3d &e_velocity)
Set the Velocity in the earth frame.
Definition PosVel.hpp:216
static std::string type()
Returns the type of the data class.
Definition PosVel.hpp:27
void setVelocity_n(const Eigen::Vector3d &n_velocity)
Set the Velocity in the NED frame.
Definition PosVel.hpp:224
const Eigen::Vector3d & e_velocity() const
Returns the velocity in [m/s], in earth coordinates.
Definition PosVel.hpp:193
std::optional< double > getValueAt(size_t idx) const override
Get the value at the index.
Definition PosVel.hpp:80
void setVelocityAndStdDev_n(const Eigen::Vector3d &n_velocity, const Eigen::Matrix3d &n_velocityCovarianceMatrix)
Set the Velocity in NED coordinates and its standard deviation.
Definition PosVel.hpp:243
void setPositionAndStdDev_e(const Eigen::Vector3d &e_position, const Eigen::Matrix3d &e_positionCovarianceMatrix)
Set the Position in ECEF coordinates and its standard deviation.
Definition Pos.hpp:237
Eigen::Quaterniond e_Quat_n() const
Returns the Quaternion from navigation to Earth-fixed frame.
Definition Pos.hpp:153
void setPositionAndStdDev_lla(const Eigen::Vector3d &lla_position, const Eigen::Matrix3d &n_positionCovarianceMatrix)
Set the Position in LLA coordinates and its standard deviation.
Definition Pos.hpp:247
Eigen::Quaterniond n_Quat_e() const
Returns the Quaternion from Earth-fixed frame to navigation.
Definition Pos.hpp:160
const Eigen::Vector3d & e_position() const
Returns the coordinates in [m].
Definition Pos.hpp:200
const Eigen::Vector3d & lla_position() const
Returns the latitude 𝜙, longitude λ and altitude (height above ground) in [rad, rad,...
Definition Pos.hpp:188
void setPosition_e(const Eigen::Vector3d &e_position)
Set the Position in coordinates.
Definition Pos.hpp:220
void setPosition_lla(const Eigen::Vector3d &lla_position)
Set the Position lla object.
Definition Pos.hpp:228