#include <Rot3d.h>
| Public Member Functions | |
| Rot3d | exmap (const Eigen::VectorXd &delta) const | 
| Eigen::Matrix3d | oRw () const | 
| double | pitch () const | 
| Eigen::Quaterniond | quaternion () const | 
| double | roll () const | 
| Rot3d () | |
| Rot3d (const Eigen::Quaterniond &quat) | |
| Rot3d (double yaw, double pitch, double roll) | |
| Rot3d (const Eigen::Matrix3d &wRo) | |
| void | set (double yaw, double pitch, double roll) | 
| void | set_pitch (double pitch) | 
| void | set_roll (double roll) | 
| void | set_yaw (double yaw) | 
| double | w () const | 
| void | write (std::ostream &out) const | 
| const Eigen::Matrix3d & | wRo () const | 
| double | x () const | 
| double | y () const | 
| double | yaw () const | 
| void | ypr (double &yaw, double &pitch, double &roll) const | 
| double | z () const | 
| Static Public Member Functions | |
| static Eigen::Quaterniond | delta3_to_quat (const Eigen::Vector3d &delta) | 
| static Eigen::Quaterniond | euler_to_quat (double yaw, double pitch, double roll) | 
| static EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix3d | euler_to_wRo (double yaw, double pitch, double roll) | 
| static const char * | name () | 
| static void | quat_to_euler (Eigen::Quaterniond q, double &yaw, double &pitch, double &roll) | 
| static Eigen::Matrix3d | quat_to_wRo (const Eigen::Quaterniond &quat) | 
| static void | wRo_to_euler (const Eigen::Matrix3d &wRo, double &yaw, double &pitch, double &roll) | 
| static Eigen::Quaterniond | wRo_to_quat (const Eigen::Matrix3d &wRo) | 
| Static Public Attributes | |
| static const int | dim = 3 | 
| static const int | size = 4 | 
| Private Member Functions | |
| void | ensure_ypr () const | 
| Private Attributes | |
| double | _pitch | 
| Eigen::Quaterniond | _quat | 
| double | _roll | 
| Eigen::Matrix3d | _wRo | 
| bool | _wRo_cached | 
| double | _yaw | 
| bool | _ypr_cached | 
| Friends | |
| std::ostream & | operator<< (std::ostream &out, const Rot3d &p) | 
| isam::Rot3d::Rot3d | ( | ) |  [inline] | 
| isam::Rot3d::Rot3d | ( | const Eigen::Quaterniond & | quat | ) |  [inline] | 
| isam::Rot3d::Rot3d | ( | double | yaw, | 
| double | pitch, | ||
| double | roll | ||
| ) |  [inline] | 
| isam::Rot3d::Rot3d | ( | const Eigen::Matrix3d & | wRo | ) |  [inline] | 
| static Eigen::Quaterniond isam::Rot3d::delta3_to_quat | ( | const Eigen::Vector3d & | delta | ) |  [inline, static] | 
| void isam::Rot3d::ensure_ypr | ( | ) | const  [inline, private] | 
| static Eigen::Quaterniond isam::Rot3d::euler_to_quat | ( | double | yaw, | 
| double | pitch, | ||
| double | roll | ||
| ) |  [inline, static] | 
| static EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix3d isam::Rot3d::euler_to_wRo | ( | double | yaw, | 
| double | pitch, | ||
| double | roll | ||
| ) |  [inline, static] | 
| Rot3d isam::Rot3d::exmap | ( | const Eigen::VectorXd & | delta | ) | const  [inline] | 
| static const char* isam::Rot3d::name | ( | ) |  [inline, static] | 
| Eigen::Matrix3d isam::Rot3d::oRw | ( | ) | const  [inline] | 
| double isam::Rot3d::pitch | ( | ) | const  [inline] | 
| static void isam::Rot3d::quat_to_euler | ( | Eigen::Quaterniond | q, | 
| double & | yaw, | ||
| double & | pitch, | ||
| double & | roll | ||
| ) |  [inline, static] | 
| static Eigen::Matrix3d isam::Rot3d::quat_to_wRo | ( | const Eigen::Quaterniond & | quat | ) |  [inline, static] | 
| Eigen::Quaterniond isam::Rot3d::quaternion | ( | ) | const  [inline] | 
| double isam::Rot3d::roll | ( | ) | const  [inline] | 
| void isam::Rot3d::set | ( | double | yaw, | 
| double | pitch, | ||
| double | roll | ||
| ) |  [inline] | 
| void isam::Rot3d::set_pitch | ( | double | pitch | ) |  [inline] | 
| void isam::Rot3d::set_roll | ( | double | roll | ) |  [inline] | 
| void isam::Rot3d::set_yaw | ( | double | yaw | ) |  [inline] | 
| double isam::Rot3d::w | ( | ) | const  [inline] | 
| void isam::Rot3d::write | ( | std::ostream & | out | ) | const  [inline] | 
| const Eigen::Matrix3d& isam::Rot3d::wRo | ( | ) | const  [inline] | 
| static void isam::Rot3d::wRo_to_euler | ( | const Eigen::Matrix3d & | wRo, | 
| double & | yaw, | ||
| double & | pitch, | ||
| double & | roll | ||
| ) |  [inline, static] | 
| static Eigen::Quaterniond isam::Rot3d::wRo_to_quat | ( | const Eigen::Matrix3d & | wRo | ) |  [inline, static] | 
| double isam::Rot3d::x | ( | ) | const  [inline] | 
| double isam::Rot3d::y | ( | ) | const  [inline] | 
| double isam::Rot3d::yaw | ( | ) | const  [inline] | 
| void isam::Rot3d::ypr | ( | double & | yaw, | 
| double & | pitch, | ||
| double & | roll | ||
| ) | const  [inline] | 
| double isam::Rot3d::z | ( | ) | const  [inline] | 
| std::ostream& operator<< | ( | std::ostream & | out, | 
| const Rot3d & | p | ||
| ) |  [friend] | 
| double isam::Rot3d::_pitch  [mutable, private] | 
| Eigen::Quaterniond isam::Rot3d::_quat  [private] | 
| double isam::Rot3d::_roll  [mutable, private] | 
| Eigen::Matrix3d isam::Rot3d::_wRo  [mutable, private] | 
| bool isam::Rot3d::_wRo_cached  [mutable, private] | 
| double isam::Rot3d::_yaw  [mutable, private] | 
| bool isam::Rot3d::_ypr_cached  [mutable, private] | 
| const int isam::Rot3d::dim = 3  [static] | 
| const int isam::Rot3d::size = 4  [static] |