A class used to store a 3D pose. More...
#include <mrpt/poses/CPose3D.h>


Public Member Functions | |
| CPose3D () | |
| Default constructor, with all the coordinates to zero. | |
| CPose3D (const double x, const double y, const double z, const double yaw=0, const double pitch=0, const double roll=0) | |
| Constructor with initilization of the pose; (remember that angles are always given in radians!). | |
| CPose3D (const CPose3D &o) | |
| Copy constructor. | |
| CPose3D & | operator= (const CPose3D &o) |
| Copy operator. | |
| CPose3D (const math::CMatrixDouble &m) | |
| Constructor from a 4x4 homogeneous matrix:. | |
| CPose3D (const math::CMatrixDouble44 &m) | |
| Constructor from a 4x4 homogeneous matrix:. | |
| CPose3D (const CPose2D &) | |
| Constructor from a CPose2D object. | |
| CPose3D (const CPoint3D &) | |
| Constructor from a CPoint3D object. | |
| CPose3D (const mrpt::math::TPose3D &) | |
| Constructor from lightweight object. | |
| CPose3D (const mrpt::math::CQuaternionDouble &q, const double x, const double y, const double z) | |
| Constructor from a quaternion (which only represents the 3D rotation part) and a 3D displacement. | |
| CPose3D (const CPose3DQuat &) | |
| Constructor from a CPose3DQuat. | |
| CPose3D (bool, bool) | |
| Fast constructor that leaves all the data uninitialized - call with UNINITIALIZED_POSE as argument. | |
| void | getHomogeneousMatrix (CMatrixDouble44 &out_HM) const |
| Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation). | |
| CPose3D | operator+ (const CPose3D &b) const |
The operator is the pose compounding operator. | |
| CPoint3D | operator+ (const CPoint3D &b) const |
The operator is the pose compounding operator. | |
| CPoint3D | operator+ (const CPoint2D &b) const |
The operator is the pose compounding operator. | |
| void | addComponents (const CPose3D &p) |
| Scalar sum of components: This is diferent from poses composition, which is implemented as "+" operators. | |
| void | normalizeAngles () |
| Rebuild the internal matrix & update the yaw/pitch/roll angles within the ]-PI,PI] range (Must be called after using addComponents). | |
| void | operator*= (const double s) |
| Scalar multiplication of x,y,z,yaw,pitch & roll (angles will be wrapped to the ]-pi,pi] interval). | |
| void | sphericalCoordinates (const TPoint3D &point, double &out_range, double &out_yaw, double &out_pitch) const |
| Computes the spherical coordinates of a 3D point as seen from the 6D pose specified by this object. | |
| void | composePoint (double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL) const |
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose. | |
| void | composePoint (const TPoint3D local_point, TPoint3D &global_point) const |
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose. | |
| void | composePoint (double lx, double ly, double lz, float &gx, float &gy, float &gz) const |
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose. | |
| void | inverseComposePoint (const double gx, const double gy, const double gz, double &lx, double &ly, double &lz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL) const |
Computes the 3D point L such as . | |
| void | composeFrom (const CPose3D &A, const CPose3D &B) |
| Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids the temporary object. | |
| CPose3D & | operator+= (const CPose3D &b) |
Make . | |
| void | inverseComposeFrom (const CPose3D &A, const CPose3D &B) |
Makes this method is slightly more efficient than "this= A - B;" since it avoids the temporary object. | |
| CPose3D | operator- (const CPose3D &b) const |
Compute . | |
| double | x () const |
| Get the X coordinate. | |
| double | y () const |
| Get the Y coordinate. | |
| double | z () const |
| Get the Z coordinate. | |
| void | x (const double x_) |
| Set the X coordinate. | |
| void | y (const double y_) |
| Set the Y coordinate. | |
| void | z (const double z_) |
| Set the Z coordinate. | |
| void | x_incr (const double Ax) |
| Increment the X coordinate. | |
| void | y_incr (const double Ay) |
| Increment the Y coordinate. | |
| void | z_incr (const double Az) |
| Increment the Z coordinate. | |
| void | setFromValues (const double x0, const double y0, const double z0, const double yaw=0, const double pitch=0, const double roll=0) |
| Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes the internal homogeneous coordinates matrix. | |
| template<typename VECTORLIKE > | |
| void | setFromXYZQ (const VECTORLIKE &v, const size_t index_offset=0) |
| Set the pose from a 3D position (meters) and a quaternion, stored as [x y z qr qx qy qz] in a 7-element vector. | |
| void | setYawPitchRoll (const double yaw_, const double pitch_, const double roll_) |
| Set the 3 angles of the 3D pose (in radians) - This method recomputes the internal homogeneous coordinates matrix. | |
| void | getYawPitchRoll (double &yaw, double &pitch, double &roll) |
| Returns the three angles (yaw, pitch, roll), in radians, from the homogeneous matrix. | |
| double | yaw () const |
| Get the YAW angle (in radians). | |
| double | pitch () const |
| Get the PITCH angle (in radians). | |
| double | roll () const |
| Get the ROLL angle (in radians). | |
| double | distanceEuclidean6D (const CPose3D &o) const |
| The euclidean distance between two poses taken as two 6-length vectors (angles in radians). | |
| void | getAsVector (vector_double &v) const |
| Returns a 1x6 vector with [x y z yaw pitch roll]. | |
| void | getAsQuaternion (mrpt::math::CQuaternionDouble &q, mrpt::math::CMatrixFixedNumeric< double, 4, 3 > *out_dq_dr=NULL) const |
| Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored)
| |
| void | asString (std::string &s) const |
| Returns a human-readable textual representation of the object (eg: "[x y z yaw pitch roll]", angles in degrees. | |
| std::string | asString () const |
| void | fromString (const std::string &s) |
| Set the current object value from a string generated by 'asString' (eg: "[0.02 1.04 -0.8]" ). | |
| bool | isHorizontal (const double tolerance=0) const |
| Return true if the 6D pose represents a Z axis almost exactly vertical (upwards or downwards), with a given tolerance (if set to 0 exact horizontality is tested). | |
| const double & | operator[] (unsigned int i) const |
Protected Member Functions | |
| void | rebuildHomogeneousMatrix () |
| Rebuild the homog matrix from x,y,z and the angles. | |
Protected Attributes | |
| double | m_yaw |
| double | m_pitch |
| double | m_roll |
| These variables are updated every time that the object homogeneous matrix is modified (construction, loading from values, pose composition, etc ). | |
| CMatrixDouble44 | m_HM |
| The homogeneous matrix. | |
Friends | |
| class | CPose |
| class | CPose2D |
| class | CPoint |
| std::ostream BASE_IMPEXP & | operator<< (std::ostream &o, const CPose3D &p) |
STL-like methods and typedefs | |
|
| |
| enum | { static_size = 6 } |
| typedef double | value_type |
| The type of the elements. | |
| typedef double & | reference |
| typedef const double & | const_reference |
| typedef std::size_t | size_type |
| typedef std::ptrdiff_t | difference_type |
| static size_type | size () |
| static bool | empty () |
| static size_type | max_size () |
| static void | resize (const size_t n) |
A class used to store a 3D pose.
A class used to store a 3D (6D) pose, including the 3D coordinate point and orientation angles. It is used in many situations, from defining a robot pose, maps relative poses, sensors,... See introduction in documentation for the CPoseOrPoint class.
For a complete description of Points/Poses, see mrpt::poses::CPoseOrPoint
For a complete description of Points/Poses, see mrpt::poses::CPoseOrPoint, or refer to the 2D/3D Geometry tutorial in the wiki.
To change the individual components of the pose, use CPose3D::setFromValues. This class assures that the internal 4x4 homogeneous coordinate matrix is always up-to-date with the "x y z yaw pitch roll" members.
Rotations in 3D can be also represented by quaternions. See mrpt::math::CQuaternion, and method CPose3D::getAsQuaternion.
This class and CPose3DQuat are very similar, and they can be converted to the each other automatically via transformation constructors.
|
Homogeneous transfomation matrix |
Spatial representation | ||||||||||||||||
where: cy = cos Yaw ; sy = sin Yaw cp = cos Pitch ; sp = sin Pitch cr = cos Roll ; sr = sin Roll |
| ||||||||||||||||
Definition at line 169 of file CPose3D.h.
| typedef const double& mrpt::poses::CPose3D::const_reference |
| typedef std::ptrdiff_t mrpt::poses::CPose3D::difference_type |
| typedef double& mrpt::poses::CPose3D::reference |
| typedef std::size_t mrpt::poses::CPose3D::size_type |
| typedef double mrpt::poses::CPose3D::value_type |
| mrpt::poses::CPose3D::CPose3D | ( | ) |
Default constructor, with all the coordinates to zero.
| mrpt::poses::CPose3D::CPose3D | ( | const double | x, | |
| const double | y, | |||
| const double | z, | |||
| const double | yaw = 0, |
|||
| const double | pitch = 0, |
|||
| const double | roll = 0 | |||
| ) |
Constructor with initilization of the pose; (remember that angles are always given in radians!).
| mrpt::poses::CPose3D::CPose3D | ( | const CPose3D & | o | ) |
Copy constructor.
| mrpt::poses::CPose3D::CPose3D | ( | const math::CMatrixDouble & | m | ) | [explicit] |
Constructor from a 4x4 homogeneous matrix:.
| mrpt::poses::CPose3D::CPose3D | ( | const math::CMatrixDouble44 & | m | ) | [explicit] |
Constructor from a 4x4 homogeneous matrix:.
| mrpt::poses::CPose3D::CPose3D | ( | const mrpt::math::TPose3D & | ) |
Constructor from lightweight object.
| mrpt::poses::CPose3D::CPose3D | ( | const mrpt::math::CQuaternionDouble & | q, | |
| const double | x, | |||
| const double | y, | |||
| const double | z | |||
| ) |
Constructor from a quaternion (which only represents the 3D rotation part) and a 3D displacement.
| mrpt::poses::CPose3D::CPose3D | ( | const CPose3DQuat & | ) |
Constructor from a CPose3DQuat.
| mrpt::poses::CPose3D::CPose3D | ( | bool | , | |
| bool | ||||
| ) | [inline] |
| void mrpt::poses::CPose3D::addComponents | ( | const CPose3D & | p | ) |
Scalar sum of components: This is diferent from poses composition, which is implemented as "+" operators.
| std::string mrpt::poses::CPose3D::asString | ( | ) | const [inline] |
| void mrpt::poses::CPose3D::asString | ( | std::string & | s | ) | const [inline, virtual] |
Returns a human-readable textual representation of the object (eg: "[x y z yaw pitch roll]", angles in degrees.
)
Implements mrpt::poses::CPoseOrPoint.
Definition at line 407 of file CPose3D.h.
References mrpt::format(), and mrpt::utils::RAD2DEG().
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids the temporary object.
Referenced by mrpt::slam::PF_implementation< PARTICLE_TYPE >::PF_SLAM_aux_perform_one_rejection_sampling_step(), and mrpt::slam::PF_implementation< PARTICLE_TYPE >::PF_SLAM_particlesEvaluator_AuxPFStandard().
| void mrpt::poses::CPose3D::composePoint | ( | double | lx, | |
| double | ly, | |||
| double | lz, | |||
| float & | gx, | |||
| float & | gy, | |||
| float & | gz | |||
| ) | const [inline] |
| void mrpt::poses::CPose3D::composePoint | ( | const TPoint3D | local_point, | |
| TPoint3D & | global_point | |||
| ) | const [inline] |
An alternative, slightly more efficient way of doing
with G and L being 3D points and P this 6D pose.
Definition at line 277 of file CPose3D.h.
References mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
| void mrpt::poses::CPose3D::composePoint | ( | double | lx, | |
| double | ly, | |||
| double | lz, | |||
| double & | gx, | |||
| double & | gy, | |||
| double & | gz, | |||
| mrpt::math::CMatrixFixedNumeric< double, 3, 3 > * | out_jacobian_df_dpoint = NULL, |
|||
| mrpt::math::CMatrixFixedNumeric< double, 3, 6 > * | out_jacobian_df_dpose = NULL | |||
| ) | const |
An alternative, slightly more efficient way of doing
with G and L being 3D points and P this 6D pose.
Referenced by mrpt::math::project3D().
| double mrpt::poses::CPose3D::distanceEuclidean6D | ( | const CPose3D & | o | ) | const |
The euclidean distance between two poses taken as two 6-length vectors (angles in radians).
| static bool mrpt::poses::CPose3D::empty | ( | ) | [inline, static] |
| void mrpt::poses::CPose3D::fromString | ( | const std::string & | s | ) | [inline, virtual] |
Set the current object value from a string generated by 'asString' (eg: "[0.02 1.04 -0.8]" ).
| std::exception | On invalid format |
Implements mrpt::poses::CPoseOrPoint.
Definition at line 414 of file CPose3D.h.
References ASSERTMSG_, mrpt::utils::DEG2RAD(), mrpt::math::CMatrixTemplate< T >::fromMatlabStringFormat(), mrpt::math::CMatrixTemplate< T >::get_unsafe(), mrpt::math::size(), and THROW_EXCEPTION.
| void mrpt::poses::CPose3D::getAsQuaternion | ( | mrpt::math::CQuaternionDouble & | q, | |
| mrpt::math::CMatrixFixedNumeric< double, 4, 3 > * | out_dq_dr = NULL | |||
| ) | const |
Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored)
With :
,
and
.
| out_dq_dr | If provided, the 4x3 Jacobian of the transformation will be computed and stored here. It's the Jacobian of the transformation from (yaw pitch roll) to (qr qx qy qz). |
Referenced by mrpt::math::jacobians::jacob_quat_from_yawpitchroll().
| void mrpt::poses::CPose3D::getAsVector | ( | vector_double & | v | ) | const [virtual] |
Returns a 1x6 vector with [x y z yaw pitch roll].
Implements mrpt::poses::CPoseOrPoint.
| void mrpt::poses::CPose3D::getHomogeneousMatrix | ( | CMatrixDouble44 & | out_HM | ) | const [inline, virtual] |
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).
Implements mrpt::poses::CPoseOrPoint.
| void mrpt::poses::CPose3D::getYawPitchRoll | ( | double & | yaw, | |
| double & | pitch, | |||
| double & | roll | |||
| ) |
Returns the three angles (yaw, pitch, roll), in radians, from the homogeneous matrix.
Makes
this method is slightly more efficient than "this= A - B;" since it avoids the temporary object.
Referenced by operator-().
| void mrpt::poses::CPose3D::inverseComposePoint | ( | const double | gx, | |
| const double | gy, | |||
| const double | gz, | |||
| double & | lx, | |||
| double & | ly, | |||
| double & | lz, | |||
| mrpt::math::CMatrixFixedNumeric< double, 3, 3 > * | out_jacobian_df_dpoint = NULL, |
|||
| mrpt::math::CMatrixFixedNumeric< double, 3, 6 > * | out_jacobian_df_dpose = NULL | |||
| ) | const |
Computes the 3D point L such as
.
| bool mrpt::poses::CPose3D::isHorizontal | ( | const double | tolerance = 0 |
) | const |
Return true if the 6D pose represents a Z axis almost exactly vertical (upwards or downwards), with a given tolerance (if set to 0 exact horizontality is tested).
| static size_type mrpt::poses::CPose3D::max_size | ( | ) | [inline, static] |
| void mrpt::poses::CPose3D::normalizeAngles | ( | ) |
Rebuild the internal matrix & update the yaw/pitch/roll angles within the ]-PI,PI] range (Must be called after using addComponents).
| void mrpt::poses::CPose3D::operator*= | ( | const double | s | ) | [virtual] |
Scalar multiplication of x,y,z,yaw,pitch & roll (angles will be wrapped to the ]-pi,pi] interval).
Implements mrpt::poses::CPoseOrPoint.
The operator
is the pose compounding operator.
The operator
is the pose compounding operator.
The operator
is the pose compounding operator.
Compute
.
Definition at line 314 of file CPose3D.h.
References inverseComposeFrom(), and UNINITIALIZED_POSE.
| const double& mrpt::poses::CPose3D::operator[] | ( | unsigned int | i | ) | const [inline] |
| double mrpt::poses::CPose3D::pitch | ( | ) | const [inline] |
| void mrpt::poses::CPose3D::rebuildHomogeneousMatrix | ( | ) | [protected] |
Rebuild the homog matrix from x,y,z and the angles.
| static void mrpt::poses::CPose3D::resize | ( | const size_t | n | ) | [inline, static] |
Definition at line 457 of file CPose3D.h.
References mrpt::format().
| double mrpt::poses::CPose3D::roll | ( | ) | const [inline] |
| void mrpt::poses::CPose3D::setFromValues | ( | const double | x0, | |
| const double | y0, | |||
| const double | z0, | |||
| const double | yaw = 0, |
|||
| const double | pitch = 0, |
|||
| const double | roll = 0 | |||
| ) |
Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes the internal homogeneous coordinates matrix.
| void mrpt::poses::CPose3D::setFromXYZQ | ( | const VECTORLIKE & | v, | |
| const size_t | index_offset = 0 | |||
| ) | [inline] |
Set the pose from a 3D position (meters) and a quaternion, stored as [x y z qr qx qy qz] in a 7-element vector.
Definition at line 350 of file CPose3D.h.
References ASSERT_.
| void mrpt::poses::CPose3D::setYawPitchRoll | ( | const double | yaw_, | |
| const double | pitch_, | |||
| const double | roll_ | |||
| ) | [inline] |
Set the 3 angles of the 3D pose (in radians) - This method recomputes the internal homogeneous coordinates matrix.
| static size_type mrpt::poses::CPose3D::size | ( | ) | [inline, static] |
| void mrpt::poses::CPose3D::sphericalCoordinates | ( | const TPoint3D & | point, | |
| double & | out_range, | |||
| double & | out_yaw, | |||
| double & | out_pitch | |||
| ) | const |
Computes the spherical coordinates of a 3D point as seen from the 6D pose specified by this object.
For the coordinate system see the top of this page.
| void mrpt::poses::CPose3D::x | ( | const double | x_ | ) | [inline, virtual] |
Set the X coordinate.
Reimplemented from mrpt::poses::CPoseOrPoint.
| double mrpt::poses::CPose3D::x | ( | ) | const [inline] |
Get the X coordinate.
Reimplemented from mrpt::poses::CPoseOrPoint.
| void mrpt::poses::CPose3D::x_incr | ( | const double | Ax | ) | [inline, virtual] |
Increment the X coordinate.
Reimplemented from mrpt::poses::CPoseOrPoint.
| void mrpt::poses::CPose3D::y | ( | const double | y_ | ) | [inline, virtual] |
Set the Y coordinate.
Reimplemented from mrpt::poses::CPoseOrPoint.
| double mrpt::poses::CPose3D::y | ( | ) | const [inline] |
Get the Y coordinate.
Reimplemented from mrpt::poses::CPoseOrPoint.
| void mrpt::poses::CPose3D::y_incr | ( | const double | Ay | ) | [inline, virtual] |
Increment the Y coordinate.
Reimplemented from mrpt::poses::CPoseOrPoint.
| double mrpt::poses::CPose3D::yaw | ( | ) | const [inline] |
| void mrpt::poses::CPose3D::z | ( | const double | z_ | ) | [inline, virtual] |
Set the Z coordinate.
Reimplemented from mrpt::poses::CPoseOrPoint.
| double mrpt::poses::CPose3D::z | ( | ) | const [inline] |
Get the Z coordinate.
Reimplemented from mrpt::poses::CPoseOrPoint.
| void mrpt::poses::CPose3D::z_incr | ( | const double | Az | ) | [inline, virtual] |
Increment the Z coordinate.
Reimplemented from mrpt::poses::CPoseOrPoint.
| std::ostream BASE_IMPEXP& operator<< | ( | std::ostream & | o, | |
| const CPose3D & | p | |||
| ) | [friend] |
CMatrixDouble44 mrpt::poses::CPose3D::m_HM [mutable, protected] |
double mrpt::poses::CPose3D::m_pitch [protected] |
double mrpt::poses::CPose3D::m_roll [protected] |
double mrpt::poses::CPose3D::m_yaw [protected] |
| Page generated by Doxygen 1.6.1 for MRPT 0.9.0 SVN: at Mon Jun 7 06:47:58 UTC 2010 |