API Documentation
Loading...
Searching...
No Matches
MocapMeasurement Class Reference

#include <GPSTypes.h>

Inheritance diagram for MocapMeasurement:
[legend]
Collaboration diagram for MocapMeasurement:
[legend]

Public Member Functions

Eigen::MatrixXd getCovariance () const override
 
Eigen::Vector3d getRelativeFromOrigin (const GlobalPosition &origin) const override
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MocapMeasurement ()
 
 MocapMeasurement (const int id, const double &x, const double &y, const double &z, const double &qx, const double &qy, const double &qz, const double &qw, const double &timestamp, const Eigen::Matrix3d &covariance, const Eigen::Vector3d noise=Eigen::Vector3d(0., 0., 0.))
 
- Public Member Functions inherited from GlobalPosition
virtual ~GlobalPosition ()
 

Public Attributes

Eigen::Matrix3d covariance
 
Eigen::Vector3d noise
 
Eigen::Vector3d position
 
Eigen::Quaterniond rotation
 
- Public Attributes inherited from GlobalPosition
int id
 
double timestamp
 

Additional Inherited Members

- Protected Member Functions inherited from GlobalPosition
 GlobalPosition ()
 
 GlobalPosition (int id, double timestamp)
 

Constructor & Destructor Documentation

◆ MocapMeasurement() [1/2]

EIGEN_MAKE_ALIGNED_OPERATOR_NEW MocapMeasurement ( )
inline

◆ MocapMeasurement() [2/2]

MocapMeasurement ( const int id,
const double & x,
const double & y,
const double & z,
const double & qx,
const double & qy,
const double & qz,
const double & qw,
const double & timestamp,
const Eigen::Matrix3d & covariance,
const Eigen::Vector3d noise = Eigen::Vector3d(0., 0., 0.) )
inline

Member Function Documentation

◆ getCovariance()

Eigen::MatrixXd getCovariance ( ) const
overridevirtual

Implements GlobalPosition.

◆ getRelativeFromOrigin()

Eigen::Vector3d getRelativeFromOrigin ( const GlobalPosition & origin) const
overridevirtual

Implements GlobalPosition.

Member Data Documentation

◆ covariance

Eigen::Matrix3d covariance

◆ noise

Eigen::Vector3d noise

◆ position

Eigen::Vector3d position

◆ rotation

Eigen::Quaterniond rotation

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