0.2.0
Loading...
Searching...
No Matches
NAV::PosVelAtt Class Reference

Position, Velocity and Attitude Storage Class. More...

Public Member Functions

Eigen::Quaterniond b_Quat_e () const
 Returns the Quaternion from Earth-fixed to body frame.
 
Eigen::Quaterniond b_Quat_n () const
 Returns the Quaternion from navigation to body frame (NED)
 
const Eigen::Quaterniond & e_Quat_b () const
 Returns the Quaternion from body to Earth-fixed frame.
 
std::optional< double > getValueAt (size_t idx) const override
 Get the value at the index.
 
const Eigen::Quaterniond & n_Quat_b () const
 Returns the Quaternion from body to navigation frame (NED)
 
Eigen::Vector3d rollPitchYaw () const
 Returns the Roll, Pitch and Yaw angles in [rad].
 
void setAttitude_e_Quat_b (const Eigen::Quaterniond &e_Quat_b)
 Set the Quaternion from body to earth frame.
 
void setAttitude_n_Quat_b (const Eigen::Quaterniond &n_Quat_b)
 Set the Quaternion from body to navigation frame.
 
void setState_e (const Eigen::Vector3d &e_position, const Eigen::Vector3d &e_velocity, const Eigen::Quaterniond &e_Quat_b)
 Set the State.
 
void setState_n (const Eigen::Vector3d &lla_position, const Eigen::Vector3d &n_velocity, const Eigen::Quaterniond &n_Quat_b)
 Set the State.
 
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.
 
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.
 
std::vector< std::string > staticDataDescriptors () const override
 Returns a vector of data descriptors.
 
size_t staticDescriptorCount () const override
 Get the amount of descriptors.
 
- Public Member Functions inherited from NAV::PosVel
std::optional< std::reference_wrapper< const KeyedMatrixXd< States::StateKeys, States::StateKeys > > > e_CovarianceMatrix () const
 Returns the Covariance matrix in ECEF frame.
 
const Eigen::Vector3d & e_velocity () const
 Returns the velocity in [m/s], in earth coordinates.
 
std::optional< std::reference_wrapper< const Eigen::Vector3d > > e_velocityStdev () const
 Returns the standard deviation of the velocity in [m/s], in earth coordinates.
 
std::optional< std::reference_wrapper< const KeyedMatrixXd< States::StateKeys, States::StateKeys > > > n_CovarianceMatrix () const
 Returns the Covariance matrix in local navigation frame.
 
const Eigen::Vector3d & n_velocity () const
 Returns the velocity in [m/s], in navigation coordinates.
 
std::optional< std::reference_wrapper< const Eigen::Vector3d > > n_velocityStdev () const
 Returns the standard deviation of the velocity in [m/s], in navigation coordinates.
 
template<typename Derived >
void setPosVelCovarianceMatrix_e (const Eigen::MatrixBase< Derived > &e_covarianceMatrix)
 Set the Covariance matrix in ECEF coordinates.
 
template<typename Derived >
void setPosVelCovarianceMatrix_n (const Eigen::MatrixBase< Derived > &n_covarianceMatrix)
 Set the Covariance matrix in NED coordinates.
 
void setVelocity_e (const Eigen::Vector3d &e_velocity)
 Set the Velocity in the earth frame.
 
void setVelocity_n (const Eigen::Vector3d &n_velocity)
 Set the Velocity in the NED frame.
 
void setVelocityAndStdDev_e (const Eigen::Vector3d &e_velocity, const Eigen::Matrix3d &e_velocityCovarianceMatrix)
 Set the Velocity in ECEF coordinates and its standard deviation.
 
void setVelocityAndStdDev_n (const Eigen::Vector3d &n_velocity, const Eigen::Matrix3d &n_velocityCovarianceMatrix)
 Set the Velocity in NED coordinates and its standard deviation.
 
- Public Member Functions inherited from NAV::Pos
const double & altitude () const
 Returns the altitude (height above ground) in [m].
 
std::optional< std::reference_wrapper< const KeyedMatrixXd< States::StateKeys, States::StateKeys > > > e_CovarianceMatrix () const
 Returns the Covariance matrix in ECEF frame.
 
const Eigen::Vector3d & e_position () const
 Returns the coordinates in [m].
 
std::optional< std::reference_wrapper< const Eigen::Vector3d > > e_positionStdev () const
 Returns the standard deviation of the position in ECEF frame coordinates in [m].
 
Eigen::Quaterniond e_Quat_n () const
 Returns the Quaternion from navigation to Earth-fixed frame.
 
const double & latitude () const
 Returns the latitude 𝜙 in [rad].
 
const Eigen::Vector3d & lla_position () const
 Returns the latitude 𝜙, longitude λ and altitude (height above ground) in [rad, rad, m].
 
const double & longitude () const
 Returns the longitude λ in [rad].
 
std::optional< std::reference_wrapper< const KeyedMatrixXd< States::StateKeys, States::StateKeys > > > n_CovarianceMatrix () const
 Returns the Covariance matrix in local navigation frame.
 
std::optional< std::reference_wrapper< const Eigen::Vector3d > > n_positionStdev () const
 Returns the standard deviation of the position in local navigation frame coordinates in [m].
 
Eigen::Quaterniond n_Quat_e () const
 Returns the Quaternion from Earth-fixed frame to navigation.
 
template<typename Derived >
void setPosCovarianceMatrix_e (const Eigen::MatrixBase< Derived > &e_covarianceMatrix)
 Set the Covariance matrix in ECEF coordinates.
 
template<typename Derived >
void setPosCovarianceMatrix_n (const Eigen::MatrixBase< Derived > &n_covarianceMatrix)
 Set the Covariance matrix in ECEF coordinates.
 
void setPosition_e (const Eigen::Vector3d &e_position)
 Set the Position in coordinates.
 
void setPosition_lla (const Eigen::Vector3d &lla_position)
 Set the Position lla object.
 
void setPositionAndStdDev_e (const Eigen::Vector3d &e_position, const Eigen::Matrix3d &e_positionCovarianceMatrix)
 Set the Position in ECEF coordinates and its standard deviation.
 
void setPositionAndStdDev_lla (const Eigen::Vector3d &lla_position, const Eigen::Matrix3d &n_positionCovarianceMatrix)
 Set the Position in LLA coordinates and its standard deviation.
 
- Public Member Functions inherited from NAV::NodeData
void addEvent (const std::string &text)
 Adds the event to the list.
 
virtual std::vector< std::string > dynamicDataDescriptors () const
 Returns a vector of data descriptors for the dynamic data.
 
const std::vector< std::string > & events () const
 Returns a vector of string events associated with this data.
 
virtual std::vector< std::pair< std::string, double > > getDynamicData () const
 Returns a vector of data descriptors and values for the dynamic data.
 
virtual std::optional< double > getDynamicDataAt (const std::string &) const
 Get the value for the descriptor.
 
double getValueAtOrNaN (size_t idx) const
 Get the value at the index or NaN if not in the observation.
 
 NodeData ()=default
 Default constructor.
 
 NodeData (const NodeData &)=default
 Copy constructor.
 
 NodeData (NodeData &&)=default
 Move constructor.
 
NodeDataoperator= (const NodeData &)=default
 Copy assignment operator.
 
NodeDataoperator= (NodeData &&)=default
 Move assignment operator.
 
virtual ~NodeData ()=default
 Destructor.
 

Static Public Member Functions

static std::vector< std::string > GetStaticDataDescriptors ()
 Returns a vector of data descriptors.
 
static constexpr size_t GetStaticDescriptorCount ()
 Get the amount of descriptors.
 
static std::vector< std::string > parentTypes ()
 Returns the parent types of the data class.
 
static std::string type ()
 Returns the type of the data class.
 
- Static Public Member Functions inherited from NAV::PosVel
static std::vector< std::string > GetStaticDataDescriptors ()
 Returns a vector of data descriptors.
 
static constexpr size_t GetStaticDescriptorCount ()
 Get the amount of descriptors.
 
static std::vector< std::string > parentTypes ()
 Returns the parent types of the data class.
 
static std::string type ()
 Returns the type of the data class.
 
- Static Public Member Functions inherited from NAV::Pos
static std::vector< std::string > GetStaticDataDescriptors ()
 Returns a vector of data descriptors.
 
static constexpr size_t GetStaticDescriptorCount ()
 Get the amount of descriptors.
 
static std::vector< std::string > parentTypes ()
 Returns the parent types of the data class.
 
static std::string type ()
 Returns the type of the data class.
 
- Static Public Member Functions inherited from NAV::NodeData
static std::vector< std::string > GetStaticDataDescriptors ()
 Returns a vector of data descriptors.
 
static constexpr size_t GetStaticDescriptorCount ()
 Get the amount of descriptors.
 
static std::vector< std::string > parentTypes ()
 Returns the parent types of the data class.
 
static std::string type ()
 Returns the type of the data class.
 

Additional Inherited Members

- Public Attributes inherited from NAV::NodeData
InsTime insTime
 Time at which the message was received.
 
- Protected Attributes inherited from NAV::NodeData
std::vector< std::string > _events
 List of events.
 

Detailed Description

Position, Velocity and Attitude Storage Class.

Member Function Documentation

◆ b_Quat_e()

Eigen::Quaterniond NAV::PosVelAtt::b_Quat_e ( ) const
inline

Returns the Quaternion from Earth-fixed to body frame.

Returns
The Quaternion for the rotation from earth to body coordinates

◆ b_Quat_n()

Eigen::Quaterniond NAV::PosVelAtt::b_Quat_n ( ) const
inline

Returns the Quaternion from navigation to body frame (NED)

Returns
The Quaternion for the rotation from navigation to body coordinates

◆ e_Quat_b()

const Eigen::Quaterniond & NAV::PosVelAtt::e_Quat_b ( ) const
inline

Returns the Quaternion from body to Earth-fixed frame.

Returns
The Quaternion for the rotation from body to earth coordinates

◆ getValueAt()

std::optional< double > NAV::PosVelAtt::getValueAt ( size_t idx) const
inlineoverridevirtual

Get the value at the index.

Parameters
idxIndex corresponding to data descriptor order
Returns
Value if in the observation

Reimplemented from NAV::PosVel.

◆ n_Quat_b()

const Eigen::Quaterniond & NAV::PosVelAtt::n_Quat_b ( ) const
inline

Returns the Quaternion from body to navigation frame (NED)

Returns
The Quaternion for the rotation from body to navigation coordinates

◆ parentTypes()

static std::vector< std::string > NAV::PosVelAtt::parentTypes ( )
inlinestatic

Returns the parent types of the data class.

Returns
The parent data types

◆ rollPitchYaw()

Eigen::Vector3d NAV::PosVelAtt::rollPitchYaw ( ) const
inline

Returns the Roll, Pitch and Yaw angles in [rad].

Returns
[roll, pitch, yaw]^T

◆ setAttitude_e_Quat_b()

void NAV::PosVelAtt::setAttitude_e_Quat_b ( const Eigen::Quaterniond & e_Quat_b)
inline

Set the Quaternion from body to earth frame.

Parameters
[in]e_Quat_bQuaternion from body to earth frame

◆ setAttitude_n_Quat_b()

void NAV::PosVelAtt::setAttitude_n_Quat_b ( const Eigen::Quaterniond & n_Quat_b)
inline

Set the Quaternion from body to navigation frame.

Parameters
[in]n_Quat_bQuaternion from body to navigation frame

◆ setState_e()

void NAV::PosVelAtt::setState_e ( const Eigen::Vector3d & e_position,
const Eigen::Vector3d & e_velocity,
const Eigen::Quaterniond & e_Quat_b )
inline

Set the State.

Parameters
[in]e_positionNew Position in ECEF coordinates
[in]e_velocityThe new velocity in the earth frame
[in]e_Quat_bQuaternion from body to earth frame

◆ setState_n()

void NAV::PosVelAtt::setState_n ( const Eigen::Vector3d & lla_position,
const Eigen::Vector3d & n_velocity,
const Eigen::Quaterniond & n_Quat_b )
inline

Set the State.

Parameters
[in]lla_positionNew Position in LatLonAlt coordinates [rad, rad, m]
[in]n_velocityThe new velocity in the NED frame [m/s, m/s, m/s]
[in]n_Quat_bQuaternion from body to navigation frame

◆ setStateAndCovariance_e()

void NAV::PosVelAtt::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 )
inline

Set the State and the covariances.

Parameters
[in]e_positionNew Position in ECEF coordinates
[in]e_positionCovarianceMatrixStandard deviation of Position in ECEF coordinates [m]
[in]e_velocityThe new velocity in the earth frame
[in]e_velocityCovarianceMatrixCovariance matrix of Velocity in earth coordinates [m/s]
[in]e_Quat_bQuaternion from body to earth frame

◆ setStateAndCovariance_n()

void NAV::PosVelAtt::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 )
inline

Set the State and the covariances.

Parameters
[in]lla_positionNew Position in LatLonAlt coordinates [rad, rad, m]
[in]n_positionCovarianceMatrixStandard deviation of Position in NED coordinates [m]
[in]n_velocityThe new velocity in the NED frame [m/s, m/s, m/s]
[in]n_velocityCovarianceMatrixCovariance matrix of Velocity in NED coordinates [m/s]
[in]n_Quat_bQuaternion from body to navigation frame

◆ type()

static std::string NAV::PosVelAtt::type ( )
inlinestatic

Returns the type of the data class.

Returns
The data type

The documentation for this class was generated from the following file: