#include <Pose3d.h>
Public Member Functions | |
Pose3d | exmap (const Vector6d &delta) const |
Eigen::VectorXb | is_angle () const |
void | of_point2d (const Point2d &p) |
void | of_point3d (const Point3d &p) |
void | of_pose2d (const Pose2d &p) |
Pose3d | ominus (const Pose3d &b) const |
Pose3d | oplus (const Pose3d &d) const |
Eigen::Matrix4d | oTw () const |
double | pitch () const |
Pose3d () | |
Pose3d (double x, double y, double z, double yaw, double pitch, double roll) | |
Pose3d (const Eigen::MatrixXd &m) | |
Pose3d (const Eigen::Isometry3d &T) | |
Pose3d (const Point3d &t, const Rot3d &rot) | |
double | roll () const |
Rot3d | rot () const |
void | set (double x, double y, double z, double yaw, double pitch, double roll) |
void | set (const Vector6d &v) |
void | set_pitch (double pitch) |
void | set_roll (double roll) |
void | set_x (double x) |
void | set_y (double y) |
void | set_yaw (double yaw) |
void | set_z (double z) |
Point3d | trans () const |
Point3dh | transform_from (const Point3dh &p) const |
Point3d | transform_from (const Point3d &p) const |
Point3dh | transform_to (const Point3dh &p) const |
Point3d | transform_to (const Point3d &p) const |
Vector6d | vector () const |
void | write (std::ostream &out) const |
Eigen::Matrix4d | wTo () const |
double | x () const |
double | y () const |
double | yaw () const |
double | z () const |
Static Public Member Functions | |
static const char * | name () |
Static Public Attributes | |
static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const int | dim = 6 |
Private Attributes | |
Rot3d | _rot |
Point3d | _t |
Friends | |
std::ostream & | operator<< (std::ostream &out, const Pose3d &p) |
Conventions:
Right-handed coordinate system (NED: north-east-down) X forward (along default motion of robot) Y right Z down
Rotations are represented using standard Euler angles yaw pitch roll
Note that Euler angles transform objects from the global into the local frame of the vehicle: First yaw rotates around Z (changing X and Y axes to X' and Y'), then pitch around the new Y' axis, and finally roll around the new X' axis.
In contrast, the returned rotation and transformation matrices are defined in the opposite direction: wTo transforms a point from the local (second) system to the global (first) system
isam::Pose3d::Pose3d | ( | ) | [inline] |
isam::Pose3d::Pose3d | ( | double | x, |
double | y, | ||
double | z, | ||
double | yaw, | ||
double | pitch, | ||
double | roll | ||
) | [inline] |
isam::Pose3d::Pose3d | ( | const Eigen::MatrixXd & | m | ) | [inline] |
isam::Pose3d::Pose3d | ( | const Eigen::Isometry3d & | T | ) | [inline, explicit] |
isam::Pose3d::Pose3d | ( | const Point3d & | t, |
const Rot3d & | rot | ||
) | [inline] |
Pose3d isam::Pose3d::exmap | ( | const Vector6d & | delta | ) | const [inline] |
Eigen::VectorXb isam::Pose3d::is_angle | ( | ) | const [inline] |
static const char* isam::Pose3d::name | ( | ) | [inline, static] |
void isam::Pose3d::of_point2d | ( | const Point2d & | p | ) | [inline] |
void isam::Pose3d::of_point3d | ( | const Point3d & | p | ) | [inline] |
void isam::Pose3d::of_pose2d | ( | const Pose2d & | p | ) | [inline] |
Pose3d isam::Pose3d::ominus | ( | const Pose3d & | b | ) | const [inline] |
Pose3d isam::Pose3d::oplus | ( | const Pose3d & | d | ) | const [inline] |
Eigen::Matrix4d isam::Pose3d::oTw | ( | ) | const [inline] |
double isam::Pose3d::pitch | ( | ) | const [inline] |
double isam::Pose3d::roll | ( | ) | const [inline] |
Rot3d isam::Pose3d::rot | ( | ) | const [inline] |
void isam::Pose3d::set | ( | double | x, |
double | y, | ||
double | z, | ||
double | yaw, | ||
double | pitch, | ||
double | roll | ||
) | [inline] |
void isam::Pose3d::set | ( | const Vector6d & | v | ) | [inline] |
void isam::Pose3d::set_pitch | ( | double | pitch | ) | [inline] |
void isam::Pose3d::set_roll | ( | double | roll | ) | [inline] |
void isam::Pose3d::set_x | ( | double | x | ) | [inline] |
void isam::Pose3d::set_y | ( | double | y | ) | [inline] |
void isam::Pose3d::set_yaw | ( | double | yaw | ) | [inline] |
void isam::Pose3d::set_z | ( | double | z | ) | [inline] |
Point3d isam::Pose3d::trans | ( | ) | const [inline] |
Point3dh isam::Pose3d::transform_from | ( | const Point3dh & | p | ) | const [inline] |
Point3d isam::Pose3d::transform_from | ( | const Point3d & | p | ) | const [inline] |
Point3dh isam::Pose3d::transform_to | ( | const Point3dh & | p | ) | const [inline] |
Point3d isam::Pose3d::transform_to | ( | const Point3d & | p | ) | const [inline] |
Vector6d isam::Pose3d::vector | ( | ) | const [inline] |
void isam::Pose3d::write | ( | std::ostream & | out | ) | const [inline] |
Eigen::Matrix4d isam::Pose3d::wTo | ( | ) | const [inline] |
double isam::Pose3d::x | ( | ) | const [inline] |
double isam::Pose3d::y | ( | ) | const [inline] |
double isam::Pose3d::yaw | ( | ) | const [inline] |
double isam::Pose3d::z | ( | ) | const [inline] |
std::ostream& operator<< | ( | std::ostream & | out, |
const Pose3d & | p | ||
) | [friend] |
Rot3d isam::Pose3d::_rot [private] |
Point3d isam::Pose3d::_t [private] |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW const int isam::Pose3d::dim = 6 [static] |