mars_lib 0.1.0.2abe2576fe7f
Modular and Robust Sensor-Fusion
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Friends | List of all members
mars::Attitude Struct Reference

The Attitude struct. More...

#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/attitude/attitude_conversion.h>

+ Collaboration diagram for mars::Attitude:

Public Member Functions

 Attitude ()=default
 
 Attitude (const Eigen::Quaterniond &quaternion)
 
 Attitude (const Eigen::Matrix3d &rotation_matrix)
 
 Attitude (const Eigen::Vector3d &vec, const std::string &order="XYZ")
 
Eigen::Matrix3d get_rotation_matrix ()
 
Eigen::Vector2d get_rp ()
 

Public Attributes

Eigen::Quaterniond quaternion_
 

Friends

std::ostream & operator<< (std::ostream &out, const Attitude &attitude)
 

Detailed Description

The Attitude struct.

Constructor & Destructor Documentation

◆ Attitude() [1/4]

mars::Attitude::Attitude ( )
default

◆ Attitude() [2/4]

mars::Attitude::Attitude ( const Eigen::Quaterniond &  quaternion)
inline
25 : quaternion_(quaternion)
26 {
27 }
Eigen::Quaterniond quaternion_
Definition attitude_conversion.h:48

◆ Attitude() [3/4]

mars::Attitude::Attitude ( const Eigen::Matrix3d &  rotation_matrix)
inline
28 : quaternion_(rotation_matrix)
29 {
30 }

◆ Attitude() [4/4]

mars::Attitude::Attitude ( const Eigen::Vector3d &  vec,
const std::string &  order = "XYZ" 
)
inline
Todo:
TODO other orders need to be implemented
32 {
33 // scoping
34 using AAd = Eigen::AngleAxisd;
35 using v3d = Eigen::Vector3d;
36
38 if (order == "XYZ")
39 {
40 quaternion_ = AAd(vec(0), v3d::UnitX()) * AAd(vec(1), v3d::UnitY()) * AAd(vec(2), v3d::UnitZ());
41 }
42 else if (order == "ZYX")
43 {
44 quaternion_ = AAd(vec(2), v3d::UnitZ()) * AAd(vec(1), v3d::UnitY()) * AAd(vec(0), v3d::UnitX());
45 }
46 }

Member Function Documentation

◆ get_rotation_matrix()

Eigen::Matrix3d mars::Attitude::get_rotation_matrix ( )
inline
51 {
52 return quaternion_.toRotationMatrix();
53 }

◆ get_rp()

Eigen::Vector2d mars::Attitude::get_rp ( )
inline
56 {
57 Eigen::Vector3d rpy = mars::Utils::RPYFromRotMat(quaternion_.toRotationMatrix());
58 return { rpy(0), rpy(1) };
59 }
static Eigen::Vector3d RPYFromRotMat(const Eigen::Matrix3d &rot_mat)
RPYFromRotMat derives the roll pitch and yaw angle from a rotation matrix (in that order)
+ Here is the call graph for this function:
+ Here is the caller graph for this function:

Friends And Related Symbol Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  out,
const Attitude attitude 
)
friend

Member Data Documentation

◆ quaternion_

Eigen::Quaterniond mars::Attitude::quaternion_

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