#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/type_definitions/mars_types.h>
|
Eigen::Vector3d | p_ { Eigen::Vector3d::Zero() } |
|
Eigen::Quaterniond | q_ { Eigen::Quaterniond::Identity() } |
|
Eigen::Vector3d | n_p_ { Eigen::Vector3d::Ones() * 0.1 } |
|
Eigen::Vector3d | n_r_ { Eigen::Vector3d::Ones() * 0.1 } |
|
◆ Pose() [1/3]
◆ Pose() [2/3]
mars::Pose::Pose |
( |
const Eigen::Vector3d & |
position, |
|
|
const Eigen::Quaterniond & |
orientation |
|
) |
| |
|
inline |
28 :
p_(position),
q_(orientation)
29 {
30 }
Eigen::Vector3d p_
Definition mars_types.h:21
Eigen::Quaterniond q_
Definition mars_types.h:22
◆ Pose() [3/3]
mars::Pose::Pose |
( |
const Eigen::Vector3d & |
position, |
|
|
const Eigen::Matrix3d & |
rotation |
|
) |
| |
|
inline |
32 :
p_(position),
q_(rotation)
33 {
34 }
◆ set_meas_noise()
void mars::Pose::set_meas_noise |
( |
Eigen::Vector3d |
n_p, |
|
|
Eigen::Vector3d |
n_r |
|
) |
| |
|
inline |
37 {
40 }
Eigen::Vector3d n_r_
Definition mars_types.h:25
Eigen::Vector3d n_p_
Definition mars_types.h:24
◆ operator==()
bool mars::Pose::operator== |
( |
const Pose & |
rhs | ) |
const |
|
inline |
43 {
44 return ((
p_ == rhs.p_) && ((
q_.coeffs() == rhs.q_.coeffs())));
45 }
◆ get_meas_noise_mat()
Eigen::Matrix< double, 6, 6 > mars::Pose::get_meas_noise_mat |
( |
| ) |
const |
|
inline |
56 {
57 Eigen::Matrix<double, 6, 1> vec;
59 return vec.asDiagonal();
60 }
◆ get_inverse_pose()
Pose mars::Pose::get_inverse_pose |
( |
| ) |
const |
|
inline |
Return inverse transformation (T_AB -> T_BA) as mars::Pose.
- Returns
- Pose
67 {
68 return Pose(-
q_.toRotationMatrix().transpose() *
p_,
q_.conjugate());
69 }
◆ operator<<
std::ostream & operator<< |
( |
std::ostream & |
out, |
|
|
const Pose & |
data |
|
) |
| |
|
friend |
48 {
49 out << "p: " << data.p_[0] << ", " << data.p_[1] << ", " << data.p_[2];
50 out << " q: " << data.q_.w() << ", " << data.q_.x() << ", " << data.q_.y() << ", " << data.q_.z();
51
52 return out;
53 }
◆ p_
Eigen::Vector3d mars::Pose::p_ { Eigen::Vector3d::Zero() } |
21{ Eigen::Vector3d::Zero() };
◆ q_
Eigen::Quaterniond mars::Pose::q_ { Eigen::Quaterniond::Identity() } |
22{ Eigen::Quaterniond::Identity() };
◆ n_p_
Eigen::Vector3d mars::Pose::n_p_ { Eigen::Vector3d::Ones() * 0.1 } |
24{ Eigen::Vector3d::Ones() * 0.1 };
◆ n_r_
Eigen::Vector3d mars::Pose::n_r_ { Eigen::Vector3d::Ones() * 0.1 } |
25{ Eigen::Vector3d::Ones() * 0.1 };
The documentation for this class was generated from the following file: