mars_lib  0.1.0.3dc76ee85e09
Modular and Robust Sensor-Fusion
Public Member Functions | Static Public Member Functions | List of all members
mars::Utils Class Reference

#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/general_functions/utils.h>

+ Collaboration diagram for mars::Utils:

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Utils ()
 

Static Public Member Functions

static std::string get_mars_version_string ()
 get_mars_version_string More...
 
static void PrintMarsVersion ()
 PrintMarsVersion. More...
 
static void TransformImu (const mars::IMUMeasurementType &prev, const mars::IMUMeasurementType &now, const double &dt, const Eigen::Vector3d &p_ab, const Eigen::Quaterniond &q_ab, mars::IMUMeasurementType &result)
 TransformImu Transform IMU measurements from current frame A to frame B. More...
 
static void TransformImu (const mars::IMUMeasurementType &now, const Eigen::Vector3d &p_ab, const Eigen::Quaterniond &q_ab, mars::IMUMeasurementType &result)
 TransformImu Transform IMU measurements from current frame A to frame B. More...
 
static Eigen::Matrix3d Skew (const Eigen::Vector3d &v)
 skew generate the skew symmetric matrix of v More...
 
static Eigen::Matrix4d MatExp (const Eigen::Matrix4d &A, const int &order=4)
 mat_exp Calculation of the matrix exponential, Taylor series cut-off at specified order More...
 
static Eigen::Matrix4d OmegaMat (const Eigen::Vector3d &v)
 omega_mat ight multiplication More...
 
static Eigen::Quaterniond QuatFromSmallAngle (const Eigen::Vector3d &d_theta_vec)
 QuatFromSmallAngle. More...
 
static Eigen::Quaterniond ApplySmallAngleQuatCorr (const Eigen::Quaterniond &q_prior, const Eigen::Vector3d &correction)
 ApplySmallAngleQuatCorr. More...
 
static Eigen::Vector3d RPYFromRotMat (const Eigen::Matrix3d &rot_mat)
 RPYFromRotMat derives the roll pitch and yaw angle from a rotation matrix (in that order) More...
 
static bool CheckCov (const Eigen::MatrixXd &cov_mat, const std::string &description, const bool &check_cond=false)
 check_cov Performs tests for the properties of a given covariance matrix More...
 
static Eigen::MatrixXd EnforceMatrixSymmetry (const Eigen::Ref< const Eigen::MatrixXd > &mat_in)
 EnforceMatrixSymmetry. More...
 
static Eigen::Quaterniond quaternionAverage (const std::vector< Eigen::Quaterniond > &quats)
 quaternionAverage without weights More...
 
template<typename T , typename A >
static std::vector< T > VecExtractEveryNthElm (std::vector< T, A > const &data, const int &nth)
 VecExtractEveryNthElm Takes a vector and returns a new vector which only contains every n'th element. More...
 
static Eigen::Quaterniond NormalizeQuaternion (const Eigen::Quaterniond &quat, std::string note="")
 
static Eigen::Quaterniond NormalizeQuaternion (const double &w, const double &x, const double &y, const double &z, std::string note="")
 

Constructor & Destructor Documentation

◆ Utils()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW mars::Utils::Utils ( )

Member Function Documentation

◆ get_mars_version_string()

static std::string mars::Utils::get_mars_version_string ( )
static

get_mars_version_string

Returns
String wit MaRS version and git commit hash

◆ PrintMarsVersion()

static void mars::Utils::PrintMarsVersion ( )
static

PrintMarsVersion.

◆ TransformImu() [1/2]

static void mars::Utils::TransformImu ( const mars::IMUMeasurementType prev,
const mars::IMUMeasurementType now,
const double &  dt,
const Eigen::Vector3d &  p_ab,
const Eigen::Quaterniond &  q_ab,
mars::IMUMeasurementType result 
)
static

TransformImu Transform IMU measurements from current frame A to frame B.

This function takes angular accleration into account and thus needs the previous IMU measurement and dt

Parameters
prevPrevios IMU measurement expressed in frame A
nowCurrent IMU measurement expressed in frame A
dtDelta time between both IMU measurements
p_abTransformation of frame B w.r.t. frame A
q_abRotation of frame B w.r.t. frame A
resultTransformed current IMU measurement expressed in frame B

◆ TransformImu() [2/2]

static void mars::Utils::TransformImu ( const mars::IMUMeasurementType now,
const Eigen::Vector3d &  p_ab,
const Eigen::Quaterniond &  q_ab,
mars::IMUMeasurementType result 
)
static

TransformImu Transform IMU measurements from current frame A to frame B.

This function does not take the angular accleration into account and thus does not need the previous IMU measurement and dt

Parameters
nowCurrent IMU measurement expressed in frame A
p_abTransformation of frame B w.r.t. frame A
q_abRotation of frame B w.r.t. frame A
resultTransformed current IMU measurement expressed in frame B

◆ Skew()

static Eigen::Matrix3d mars::Utils::Skew ( const Eigen::Vector3d &  v)
static

skew generate the skew symmetric matrix of v

Parameters
v3d vector
Returns
skew symmetric matrix
+ Here is the caller graph for this function:

◆ MatExp()

static Eigen::Matrix4d mars::Utils::MatExp ( const Eigen::Matrix4d &  A,
const int &  order = 4 
)
static

mat_exp Calculation of the matrix exponential, Taylor series cut-off at specified order

Parameters
AMatrix for Taylor series
orderOrder at wich the series is cut-off
Returns

◆ OmegaMat()

static Eigen::Matrix4d mars::Utils::OmegaMat ( const Eigen::Vector3d &  v)
static

omega_mat ight multiplication

Parameters
v
Returns
Note
Reference: Joan Sola - Quaternion Kinematics for the error-state kalman filter - Equation(199)

◆ QuatFromSmallAngle()

static Eigen::Quaterniond mars::Utils::QuatFromSmallAngle ( const Eigen::Vector3d &  d_theta_vec)
static

QuatFromSmallAngle.

Parameters
d_theta_vecangle for the generation of the quaternion
Returns
Resulting quaternion

◆ ApplySmallAngleQuatCorr()

static Eigen::Quaterniond mars::Utils::ApplySmallAngleQuatCorr ( const Eigen::Quaterniond &  q_prior,
const Eigen::Vector3d &  correction 
)
static

ApplySmallAngleQuatCorr.

Parameters
q_prior
correction
Returns
+ Here is the caller graph for this function:

◆ RPYFromRotMat()

static Eigen::Vector3d mars::Utils::RPYFromRotMat ( const Eigen::Matrix3d &  rot_mat)
static

RPYFromRotMat derives the roll pitch and yaw angle from a rotation matrix (in that order)

Parameters
rot_mat3x3 rotation matrix
Returns
Vector with [roll, pitch, yaw]
+ Here is the caller graph for this function:

◆ CheckCov()

static bool mars::Utils::CheckCov ( const Eigen::MatrixXd &  cov_mat,
const std::string &  description,
const bool &  check_cond = false 
)
static

check_cov Performs tests for the properties of a given covariance matrix

Parameters
cov_mat
descriptionUsed to associate the warning with the given covariance
check_condCheck the condition number of the covariance matrix
Returns
true if the covariance matrix is valid, false otherwise

◆ EnforceMatrixSymmetry()

static Eigen::MatrixXd mars::Utils::EnforceMatrixSymmetry ( const Eigen::Ref< const Eigen::MatrixXd > &  mat_in)
static

EnforceMatrixSymmetry.

Parameters
mat_in
Returns
+ Here is the caller graph for this function:

◆ quaternionAverage()

static Eigen::Quaterniond mars::Utils::quaternionAverage ( const std::vector< Eigen::Quaterniond > &  quats)
static

quaternionAverage without weights

Parameters
quatsvector of quaternion being averaged
Returns
Eigen::Quaterniond averaged quaternion
Note
Reference: Markley et al., Averaging Quaternions, Journal of Guidance, Control, and Dynamics, 30(4):1193-1196, June 2007

◆ VecExtractEveryNthElm()

template<typename T , typename A >
static std::vector<T> mars::Utils::VecExtractEveryNthElm ( std::vector< T, A > const &  data,
const int &  nth 
)
inlinestatic

VecExtractEveryNthElm Takes a vector and returns a new vector which only contains every n'th element.

Parameters
dataVector with a number of entries
nthDefines the reduction of entries to only every n'th
Returns
Vector with reduced entries
150  {
151  std::vector<T> every_nth_data;
152  const int len = data.size();
153 
154  for (int k = 0; k < len - nth; k += nth)
155  {
156  every_nth_data.push_back(data[k]);
157  }
158  return every_nth_data;
159  }

◆ NormalizeQuaternion() [1/2]

static Eigen::Quaterniond mars::Utils::NormalizeQuaternion ( const Eigen::Quaterniond &  quat,
std::string  note = "" 
)
static
+ Here is the caller graph for this function:

◆ NormalizeQuaternion() [2/2]

static Eigen::Quaterniond mars::Utils::NormalizeQuaternion ( const double &  w,
const double &  x,
const double &  y,
const double &  z,
std::string  note = "" 
)
static

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