The Attitude struct.
More...
#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/attitude/attitude_conversion.h>
◆ Attitude() [1/4]
mars::Attitude::Attitude |
( |
| ) |
|
|
default |
◆ Attitude() [2/4]
mars::Attitude::Attitude |
( |
const Eigen::Quaterniond & |
quaternion | ) |
|
|
inline |
Eigen::Quaterniond quaternion_
Definition: attitude_conversion.h:48
◆ Attitude() [3/4]
mars::Attitude::Attitude |
( |
const Eigen::Matrix3d & |
rotation_matrix | ) |
|
|
inline |
◆ Attitude() [4/4]
mars::Attitude::Attitude |
( |
const Eigen::Vector3d & |
vec, |
|
|
const std::string & |
order = "XYZ" |
|
) |
| |
|
inline |
- Todo:
- TODO other orders need to be implemented
34 using AAd = Eigen::AngleAxisd;
35 using v3d = Eigen::Vector3d;
40 quaternion_ = AAd(vec(0), v3d::UnitX()) * AAd(vec(1), v3d::UnitY()) * AAd(vec(2), v3d::UnitZ());
42 else if (order ==
"ZYX")
44 quaternion_ = AAd(vec(2), v3d::UnitZ()) * AAd(vec(1), v3d::UnitY()) * AAd(vec(0), v3d::UnitX());
◆ get_rotation_matrix()
Eigen::Matrix3d mars::Attitude::get_rotation_matrix |
( |
| ) |
|
|
inline |
◆ get_rp()
Eigen::Vector2d mars::Attitude::get_rp |
( |
| ) |
|
|
inline |
58 return { rpy(0), rpy(1) };
static Eigen::Vector3d RPYFromRotMat(const Eigen::Matrix3d &rot_mat)
RPYFromRotMat derives the roll pitch and yaw angle from a rotation matrix (in that order)
◆ operator<<
std::ostream& operator<< |
( |
std::ostream & |
out, |
|
|
const Attitude & |
attitude |
|
) |
| |
|
friend |
◆ quaternion_
Eigen::Quaterniond mars::Attitude::quaternion_ |
The documentation for this struct was generated from the following file: