MRPT
1.9.9
|
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
The 6D transformation in SE(3) stored in this class is kept in two separate containers: a 3-array for the translation, and a 3x3 rotation matrix.
This class allows parameterizing 6D poses as a 6-vector: [x y z yaw pitch roll] (read below for the angles convention). Note however, that the yaw/pitch/roll angles are only computed (on-demand and transparently) when the user requests them. Normally, rotations and transformations are always handled via the 3x3 rotation matrix.
Yaw/Pitch/Roll angles are defined as successive rotations around local (dynamic) axes in the Z/Y/X order:
It may be extremely confusing and annoying to find a different criterion also involving the names "yaw, pitch, roll" but regarding rotations around global (static) axes. Fortunately, it's very easy to see (by writing down the product of the three rotation matrices) that both conventions lead to exactly the same numbers. Only, that it's conventional to write the numbers in reverse order. That is, the same rotation can be described equivalently with any of these two parameterizations:
For further descriptions of point & pose classes, see mrpt::poses::CPoseOrPoint or refer to the 2D/3D Geometry tutorial online.
To change the individual components of the pose, use CPose3D::setFromValues. This class assures that the internal 3x3 rotation matrix is always up-to-date with the "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.
For Lie algebra methods, see mrpt::poses::Lie.
#include <mrpt/poses/CPose3D.h>
Public Types | |
enum | { is_3D_val = 1 } |
enum | { rotation_dimensions = 3 } |
enum | { is_PDF_val = 0 } |
using | type_value = CPose3D |
Used to emulate CPosePDF types, for example, in mrpt::graphs::CNetworkOfPoses. More... | |
using | vector_t = mrpt::math::CVectorFixedDouble< DIM > |
Fixed-size vector of the correct size to hold all the coordinates of the point/pose. More... | |
Public Member Functions | |
CPose3D | getOppositeScalar () const |
Return the opposite of the current pose instance by taking the negative of all its components individually. More... | |
void | setToNaN () override |
Set all data fields to quiet NaN. More... | |
const type_value & | getPoseMean () const |
type_value & | getPoseMean () |
const CPose3D & | derived () const |
CPose3D & | derived () |
virtual mxArray * | writeToMatlab () const |
Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class. More... | |
Access 3x3 rotation and 4x4 homogeneous matrices | |
void | getHomogeneousMatrix (mrpt::math::CMatrixDouble44 &out_HM) const |
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation). More... | |
void | getRotationMatrix (mrpt::math::CMatrixDouble33 &ROT) const |
Get the 3x3 rotation matrix. More... | |
const mrpt::math::CMatrixDouble33 & | getRotationMatrix () const |
void | setRotationMatrix (const mrpt::math::CMatrixDouble33 &ROT) |
Sets the 3x3 rotation matrix. More... | |
Pose-pose and pose-point compositions and operators | |
CPose3D | operator+ (const CPose3D &b) const |
The operator is the pose compounding operator. More... | |
CPoint3D | operator+ (const CPoint3D &b) const |
The operator is the pose compounding operator. More... | |
CPoint3D | operator+ (const CPoint2D &b) const |
The operator is the pose compounding operator. More... | |
void | sphericalCoordinates (const mrpt::math::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. More... | |
void | composePoint (double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::optional_ref< mrpt::math::CMatrixDouble33 > out_jacobian_df_dpoint=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dpose=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dse3=std::nullopt, bool use_small_rot_approx=false) const |
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose. More... | |
void | composePoint (const mrpt::math::TPoint3D &local_point, mrpt::math::TPoint3D &global_point) const |
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose. More... | |
mrpt::math::TPoint3D | composePoint (const mrpt::math::TPoint3D &l) const |
void | composePoint (const mrpt::math::TPoint3D &local_point, mrpt::math::TPoint2D &global_point) const |
This version of the method assumes that the resulting point has no Z component (use with caution!) More... | |
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. More... | |
mrpt::math::TVector3D | rotateVector (const mrpt::math::TVector3D &local) const |
Rotates a vector (i.e. More... | |
mrpt::math::TVector3D | inverseRotateVector (const mrpt::math::TVector3D &global) const |
Inverse of rotateVector(), i.e. More... | |
void | inverseComposePoint (const double gx, const double gy, const double gz, double &lx, double &ly, double &lz, mrpt::optional_ref< mrpt::math::CMatrixDouble33 > out_jacobian_df_dpoint=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dpose=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dse3=std::nullopt) const |
Computes the 3D point L such as . More... | |
void | inverseComposePoint (const mrpt::math::TPoint3D &g, mrpt::math::TPoint3D &l) const |
mrpt::math::TPoint3D | inverseComposePoint (const mrpt::math::TPoint3D &g) const |
void | inverseComposePoint (const mrpt::math::TPoint2D &g, mrpt::math::TPoint2D &l, const double eps=1e-6) const |
overload for 2D points More... | |
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. More... | |
CPose3D & | operator+= (const CPose3D &b) |
Make (b can be "this" without problems) More... | |
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. More... | |
CPose3D | operator- (const CPose3D &b) const |
Compute . More... | |
void | inverse () |
Convert this pose into its inverse, saving the result in itself. More... | |
void | changeCoordinatesReference (const CPose3D &p) |
makes: this = p (+) this More... | |
RTTI classes and functions for polymorphic hierarchies | |
mrpt::rtti::CObject::Ptr | duplicateGetSmartPtr () const |
Makes a deep copy of the object and returns a smart pointer to it. More... | |
Static Public Member Functions | |
static constexpr bool | is_3D () |
static constexpr bool | is_PDF () |
Public Attributes | |
mrpt::math::CVectorFixedDouble< 3 > | m_coords |
The translation vector [x,y,z] access directly or with x(), y(), z() setter/getter methods. More... | |
Protected Member Functions | |
void | rebuildRotationMatrix () |
Rebuild the homog matrix from the angles. More... | |
void | updateYawPitchRoll () const |
Updates Yaw/pitch/roll members from the m_ROT. More... | |
CSerializable virtual methods | |
uint8_t | serializeGetVersion () const override |
Must return the current versioning number of the object. More... | |
void | serializeTo (mrpt::serialization::CArchive &out) const override |
Pure virtual method for writing (serializing) to an abstract archive. More... | |
void | serializeFrom (mrpt::serialization::CArchive &in, uint8_t serial_version) override |
Pure virtual method for reading (deserializing) from an abstract archive. More... | |
CSerializable virtual methods | |
virtual void | serializeTo (CSchemeArchiveBase &out) const |
Virtual method for writing (serializing) to an abstract schema based archive. More... | |
virtual void | serializeFrom (CSchemeArchiveBase &in) |
Virtual method for reading (deserializing) from an abstract schema based archive. More... | |
Protected Attributes | |
mrpt::math::CMatrixDouble33 | m_ROT |
The 3x3 rotation matrix, access with getRotationMatrix(), setRotationMatrix() (It's not safe to set this field as public) More... | |
bool | m_ypr_uptodate {false} |
Whether yaw/pitch/roll members are up-to-date since the last rotation matrix update. More... | |
double | m_yaw {0} |
These variables are updated every time that the object rotation matrix is modified (construction, loading from values, pose composition, etc ) More... | |
double | m_pitch {0} |
double | m_roll {0} |
RTTI stuff | |
using | Ptr = std::shared_ptr< mrpt::poses ::CPose3D > |
using | ConstPtr = std::shared_ptr< const mrpt::poses ::CPose3D > |
using | UniquePtr = std::unique_ptr< mrpt::poses ::CPose3D > |
using | ConstUniquePtr = std::unique_ptr< const mrpt::poses ::CPose3D > |
static const mrpt::rtti::TRuntimeClassId | runtimeClassId |
static constexpr const char * | className = "mrpt::poses" "::" "CPose3D" |
static const mrpt::rtti::TRuntimeClassId * | _GetBaseClass () |
static constexpr auto | getClassName () |
static const mrpt::rtti::TRuntimeClassId & | GetRuntimeClassIdStatic () |
static std::shared_ptr< CObject > | CreateObject () |
template<typename... Args> | |
static Ptr | Create (Args &&... args) |
template<typename Alloc , typename... Args> | |
static Ptr | CreateAlloc (const Alloc &alloc, Args &&... args) |
template<typename... Args> | |
static UniquePtr | CreateUnique (Args &&... args) |
virtual const mrpt::rtti::TRuntimeClassId * | GetRuntimeClass () const override |
Returns information about the class of an object in runtime. More... | |
virtual mrpt::rtti::CObject * | clone () const override |
Returns a deep copy (clone) of the object, indepently of its class. More... | |
Constructors | |
static CPose3D | Identity () |
Returns the identity transformation. More... | |
CPose3D () | |
Default constructor, with all the coordinates set to zero. More... | |
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!) More... | |
CPose3D (const math::CMatrixDouble &m) | |
Constructor from a 4x4 homogeneous matrix - the passed matrix can be actually of any size larger than or equal 3x4, since only those first values are used (the last row of a homogeneous 4x4 matrix are always fixed). More... | |
CPose3D (const math::CMatrixDouble44 &m) | |
Constructor from a 4x4 homogeneous matrix: More... | |
template<class MATRIX33 , class VECTOR3 > | |
CPose3D (const MATRIX33 &rot, const VECTOR3 &xyz) | |
Constructor from a 3x3 rotation matrix and a the translation given as a 3-vector, a 3-array, a CPoint3D or a mrpt::math::TPoint3D. More... | |
CPose3D (const mrpt::math::CMatrixDouble33 &rot, const mrpt::math::CVectorFixedDouble< 3 > &xyz) | |
CPose3D (const CPose2D &) | |
Constructor from a CPose2D object. More... | |
CPose3D (const CPoint3D &) | |
Constructor from a CPoint3D object. More... | |
CPose3D (const mrpt::math::TPose3D &) | |
Constructor from lightweight object. More... | |
mrpt::math::TPose3D | asTPose () const |
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. More... | |
CPose3D (const CPose3DQuat &) | |
Constructor from a CPose3DQuat. More... | |
CPose3D (TConstructorFlags_Poses) | |
Fast constructor that leaves all the data uninitialized - call with UNINITIALIZED_POSE as argument. More... | |
CPose3D (const mrpt::math::CVectorFixedDouble< 12 > &vec12) | |
Constructor from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz] where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose. More... | |
Access and modify contents | |
static CPose3D | FromString (const std::string &s) |
void | addComponents (const CPose3D &p) |
Scalar sum of all 6 components: This is diferent from poses composition, which is implemented as "+" operators. More... | |
void | normalizeAngles () |
Rebuild the internal matrix & update the yaw/pitch/roll angles within the ]-PI,PI] range (Must be called after using addComponents) More... | |
void | operator*= (const double s) |
Scalar multiplication of x,y,z,yaw,pitch & roll (angles will be wrapped to the ]-pi,pi] interval). More... | |
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 rotation matrix. More... | |
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. More... | |
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 rotation coordinates matrix. More... | |
template<class ARRAYORVECTOR > | |
void | setFrom12Vector (const ARRAYORVECTOR &vec12) |
Set pose from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz] where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose. More... | |
template<class ARRAYORVECTOR > | |
void | getAs12Vector (ARRAYORVECTOR &vec12) const |
Get the pose representation as an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz] where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose. More... | |
void | getYawPitchRoll (double &yaw, double &pitch, double &roll) const |
Returns the three angles (yaw, pitch, roll), in radians, from the rotation matrix. More... | |
double | yaw () const |
Get the YAW angle (in radians) More... | |
double | pitch () const |
Get the PITCH angle (in radians) More... | |
double | roll () const |
Get the ROLL angle (in radians) More... | |
void | asVector (vector_t &v) const |
Returns a 6x1 vector with [x y z yaw pitch roll]'. More... | |
void | getAsQuaternion (mrpt::math::CQuaternionDouble &q, mrpt::optional_ref< mrpt::math::CMatrixDouble43 > out_dq_dr=std::nullopt) const |
Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored)
With : , and . More... | |
double | operator[] (unsigned int i) const |
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.) More... | |
std::string | asString () const |
void | fromString (const std::string &s) |
Set the current object value from a string generated by 'asString' (eg: "[x y z yaw pitch roll]", angles in deg. More... | |
void | fromStringRaw (const std::string &s) |
Same as fromString, but without requiring the square brackets in the string. More... | |
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). More... | |
double | distanceEuclidean6D (const CPose3D &o) const |
The euclidean distance between two poses taken as two 6-length vectors (angles in radians). More... | |
STL-like methods and typedefs | |
enum | { static_size = 6 } |
using | value_type = double |
The type of the elements. More... | |
using | reference = double & |
using | const_reference = double |
using | size_type = std::size_t |
using | difference_type = std::ptrdiff_t |
static constexpr size_type | size () |
static constexpr bool | empty () |
static constexpr size_type | max_size () |
static void | resize (const size_t n) |
static bool | is3DPoseOrPoint () |
Return true for poses or points with a Z component, false otherwise. More... | |
double | x () const |
Common members of all points & poses classes. More... | |
double & | x () |
void | x (const double v) |
double | y () const |
double & | y () |
void | y (const double v) |
void | x_incr (const double v) |
void | y_incr (const double v) |
double | sqrDistanceTo (const CPoseOrPoint< OTHERCLASS, DIM2 > &b) const |
Returns the squared euclidean distance to another pose/point: More... | |
double | distanceTo (const CPoseOrPoint< OTHERCLASS, DIM2 > &b) const |
Returns the Euclidean distance to another pose/point: More... | |
double | distanceTo (const mrpt::math::TPoint3D &b) const |
Returns the euclidean distance to a 3D point: More... | |
double | distance2DToSquare (double ax, double ay) const |
Returns the squared 2D distance from this pose/point to a 2D point (ignores Z, if it exists). More... | |
double | distance3DToSquare (double ax, double ay, double az) const |
Returns the squared 3D distance from this pose/point to a 3D point. More... | |
double | distance2DTo (double ax, double ay) const |
Returns the 2D distance from this pose/point to a 2D point (ignores Z, if it exists). More... | |
double | distance3DTo (double ax, double ay, double az) const |
Returns the 3D distance from this pose/point to a 3D point. More... | |
double | norm () const |
Returns the euclidean norm of vector: . More... | |
vector_t | asVectorVal () const |
Return the pose or point as a 1xN vector with all the components (see derived classes for each implementation) More... | |
MATRIX44 | getHomogeneousMatrixVal () const |
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation). More... | |
void | getInverseHomogeneousMatrix (MATRIX44 &out_HM) const |
Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose. More... | |
MATRIX44 | getInverseHomogeneousMatrixVal () const |
using mrpt::poses::CPose3D::const_reference = double |
using mrpt::poses::CPose3D::ConstPtr = std::shared_ptr<const mrpt::poses :: CPose3D > |
using mrpt::poses::CPose3D::ConstUniquePtr = std::unique_ptr<const mrpt::poses :: CPose3D > |
using mrpt::poses::CPose3D::difference_type = std::ptrdiff_t |
using mrpt::poses::CPose3D::Ptr = std::shared_ptr< mrpt::poses :: CPose3D > |
using mrpt::poses::CPose3D::reference = double& |
using mrpt::poses::CPose3D::size_type = std::size_t |
Used to emulate CPosePDF types, for example, in mrpt::graphs::CNetworkOfPoses.
using mrpt::poses::CPose3D::UniquePtr = std::unique_ptr< mrpt::poses :: CPose3D > |
using mrpt::poses::CPose3D::value_type = double |
|
inherited |
Fixed-size vector of the correct size to hold all the coordinates of the point/pose.
Definition at line 137 of file CPoseOrPoint.h.
CPose3D::CPose3D | ( | ) |
Default constructor, with all the coordinates set to zero.
Definition at line 52 of file CPose3D.cpp.
Referenced by changeCoordinatesReference(), getOppositeScalar(), and Identity().
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!)
Definition at line 58 of file CPose3D.cpp.
References pitch(), roll(), setFromValues(), mrpt::poses::CPoseOrPoint< CPose3D, DIM >::x(), mrpt::poses::CPoseOrPoint< CPose3D, DIM >::y(), and yaw().
|
explicit |
Constructor from a 4x4 homogeneous matrix - the passed matrix can be actually of any size larger than or equal 3x4, since only those first values are used (the last row of a homogeneous 4x4 matrix are always fixed).
Definition at line 82 of file CPose3D.cpp.
References ASSERT_ABOVEEQ_, mrpt::math::CMatrixDynamic< T >::cols(), m_coords, m_ROT, and mrpt::math::CMatrixDynamic< T >::rows().
|
explicit |
Constructor from a 4x4 homogeneous matrix:
Definition at line 92 of file CPose3D.cpp.
|
inline |
Constructor from a 3x3 rotation matrix and a the translation given as a 3-vector, a 3-array, a CPoint3D or a mrpt::math::TPoint3D.
Definition at line 153 of file CPose3D.h.
References ASSERT_EQUAL_, m_coords, and m_ROT.
|
inline |
|
explicit |
Constructor from a CPose2D object.
Definition at line 71 of file CPose3D.cpp.
References mrpt::poses::CPose2D::phi(), setFromValues(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y().
|
explicit |
Constructor from a CPoint3D object.
Definition at line 76 of file CPose3D.cpp.
References setFromValues(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y().
|
explicit |
Constructor from lightweight object.
Definition at line 66 of file CPose3D.cpp.
References mrpt::math::TPose3D::pitch, mrpt::math::TPose3D::roll, setFromValues(), mrpt::math::TPose3D::x, mrpt::math::TPose3D::y, mrpt::math::TPose3D::yaw, and mrpt::math::TPose3D::z.
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.
Definition at line 102 of file CPose3D.cpp.
References pitch(), roll(), mrpt::math::CQuaternion< T >::rpy(), setFromValues(), and yaw().
|
explicit |
Constructor from a CPose3DQuat.
Constructor from a quaternion-based full pose.
Definition at line 113 of file CPose3D.cpp.
References m_coords, m_ROT, mrpt::poses::CPose3DQuat::quat(), mrpt::math::CQuaternion< T >::rotationMatrixNoResize(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y().
|
inline |
|
inlineexplicit |
Constructor from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz] where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose.
Definition at line 207 of file CPose3D.h.
References setFrom12Vector().
|
staticprotected |
void CPose3D::addComponents | ( | const CPose3D & | p | ) |
Scalar sum of all 6 components: This is diferent from poses composition, which is implemented as "+" operators.
Definition at line 346 of file CPose3D.cpp.
References m_coords, m_pitch, m_roll, m_yaw, rebuildRotationMatrix(), and updateYawPitchRoll().
Referenced by mrpt::hmtslam::CHierarchicalMapMHPartition::getAs3DScene().
|
inline |
Returns a human-readable textual representation of the object (eg: "[x y z yaw pitch roll]", angles in degrees.)
Definition at line 618 of file CPose3D.h.
References mrpt::format(), m_coords, m_pitch, m_roll, m_yaw, mrpt::RAD2DEG(), and updateYawPitchRoll().
Referenced by mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::checkRegistrationConditionPose(), and thread_client().
|
inline |
mrpt::math::TPose3D CPose3D::asTPose | ( | ) | const |
Definition at line 759 of file CPose3D.cpp.
References pitch(), roll(), mrpt::poses::CPoseOrPoint< CPose3D, DIM >::x(), mrpt::poses::CPoseOrPoint< CPose3D, DIM >::y(), and yaw().
Referenced by mrpt::poses::CPoses3DSequence::appendPose(), mrpt::hmtslam::CLocalMetricHypothesis::changeCoordinateOrigin(), mrpt::poses::CPoses3DSequence::changePose(), mrpt::maps::CMultiMetricMapPDF::clear(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::poses::CPoseInterpolatorBase< 3 >::filter(), mrpt::slam::CMetricMapBuilderRBPF::getCurrentPoseEstimation(), mrpt::obs::CObservation::getSensorPose(), FAddUntracedLines::operator()(), mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_aux_perform_one_rejection_sampling_step(), mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_implementation_pfStandardProposal(), mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_particlesEvaluator_AuxPFOptimal(), mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_particlesEvaluator_AuxPFStandard(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::apps::ICP_SLAM_App_Base::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::apps::KFSLAMApp::Run_KF_SLAM(), mrpt::obs::CObservationGasSensors::serializeFrom(), mrpt::obs::CObservationRange::serializeFrom(), mrpt::obs::CObservationGasSensors::setSensorPose(), and mrpt::obs::CObservationRange::setSensorPose().
void CPose3D::asVector | ( | vector_t & | v | ) | const |
Returns a 6x1 vector with [x y z yaw pitch roll]'.
Definition at line 480 of file CPose3D.cpp.
References m_coords, m_pitch, m_roll, m_yaw, and updateYawPitchRoll().
|
inlineinherited |
Return the pose or point as a 1xN vector with all the components (see derived classes for each implementation)
Definition at line 266 of file CPoseOrPoint.h.
|
inline |
makes: this = p (+) this
Definition at line 423 of file CPose3D.h.
References composeFrom(), and CPose3D().
Referenced by mrpt::maps::COccupancyGridMap3D::internal_insertObservationScan3D().
|
overridevirtual |
Returns a deep copy (clone) of the object, indepently of its class.
Implements mrpt::rtti::CObject.
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids the temporary object.
Definition at line 556 of file CPose3D.cpp.
References m_coords, m_ROT, and m_ypr_uptodate.
Referenced by mrpt::poses::CPose3DPDFGaussian::changeCoordinatesReference(), changeCoordinatesReference(), mrpt::obs::CObservationVelodyneScan::generatePointCloudAlongSE3Trajectory(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CReflectivityGridMap2D::internal_computeObservationLikelihood(), mrpt::maps::CReflectivityGridMap2D::internal_insertObservation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), operator+(), mrpt::poses::CPose3DPDFGaussian::operator+=(), operator+=(), mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_aux_perform_one_rejection_sampling_step(), mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_particlesEvaluator_AuxPFStandard(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal(), mrpt::kinematics::CKinematicChain::recomputeAllPoses(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), Pose3DTests::test_composeFrom(), and mrpt::obs::detail::unprojectInto().
void mrpt::poses::CPose3D::composePoint | ( | double | lx, |
double | ly, | ||
double | lz, | ||
double & | gx, | ||
double & | gy, | ||
double & | gz, | ||
mrpt::optional_ref< mrpt::math::CMatrixDouble33 > | out_jacobian_df_dpoint = std::nullopt , |
||
mrpt::optional_ref< mrpt::math::CMatrixDouble36 > | out_jacobian_df_dpose = std::nullopt , |
||
mrpt::optional_ref< mrpt::math::CMatrixDouble36 > | out_jacobian_df_dse3 = std::nullopt , |
||
bool | use_small_rot_approx = false |
||
) | const |
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose.
If pointers are provided, the corresponding Jacobians are returned. "out_jacobian_df_dse3" stands for the Jacobian with respect to the 6D locally Euclidean vector in the tangent space of SE(3). See this report for mathematical details.
If | set to true, the Jacobian "out_jacobian_df_dpose" uses a fastest linearized appoximation (valid only for small rotations!). |
Referenced by mrpt::poses::CPointPDFParticles::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::changeCoordinatesReference(), mrpt::maps::CPointsMap::changeCoordinatesReference(), composePoint(), mrpt::maps::CPointsMap::determineMatching3D(), mrpt::vision::frameJac(), mrpt::obs::CObservationVelodyneScan::generatePointCloudAlongSE3Trajectory(), mrpt::opengl::CGridPlaneXZ::getBoundingBox(), mrpt::opengl::CGridPlaneXY::getBoundingBox(), mrpt::opengl::CAssimpModel::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CPolyhedron::getBoundingBox(), mrpt::opengl::CSetOfLines::getBoundingBox(), mrpt::opengl::CVectorField3D::getBoundingBox(), mrpt::opengl::CPolyhedron::getSetOfPolygonsAbsolute(), mrpt::opengl::internal::glDrawTextTransformed(), mrpt::maps::CPointsMap::insertAnotherMap(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CPointsMap::internal_computeObservationLikelihoodPointCloud3D(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::opengl::CArrow::onUpdateBuffers_Triangles(), mrpt::vision::pointJac(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::opengl::CGeneralizedEllipsoidTemplate< 3 >::renderUpdateBuffers(), Pose3DTests::test_composePoint(), Pose3DQuatTests::test_composePoint_vs_CPose3D(), Pose3DTests::test_composePointJacob(), and Pose3DTests::test_composePointJacob_se3().
|
inline |
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose.
Definition at line 295 of file CPose3D.h.
References composePoint(), mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Definition at line 304 of file CPose3D.h.
References composePoint().
|
inline |
This version of the method assumes that the resulting point has no Z component (use with caution!)
Definition at line 314 of file CPose3D.h.
References composePoint(), mrpt::math::TPoint2D_data< T >::x, mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint2D_data< T >::y, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.
|
inline |
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose.
Definition at line 326 of file CPose3D.h.
References composePoint(), and mrpt::d2f().
|
inlinestatic |
|
inlinestatic |
|
static |
|
inlinestatic |
|
inlineinherited |
Definition at line 129 of file CPoseOrPoint.h.
|
inlineinherited |
Definition at line 133 of file CPoseOrPoint.h.
|
inlineinherited |
Returns the 2D distance from this pose/point to a 2D point (ignores Z, if it exists).
Definition at line 237 of file CPoseOrPoint.h.
|
inlineinherited |
Returns the squared 2D distance from this pose/point to a 2D point (ignores Z, if it exists).
Definition at line 221 of file CPoseOrPoint.h.
|
inlineinherited |
Returns the 3D distance from this pose/point to a 3D point.
Definition at line 243 of file CPoseOrPoint.h.
|
inlineinherited |
Returns the squared 3D distance from this pose/point to a 3D point.
Definition at line 228 of file CPoseOrPoint.h.
double CPose3D::distanceEuclidean6D | ( | const CPose3D & | o | ) | const |
The euclidean distance between two poses taken as two 6-length vectors (angles in radians).
Definition at line 361 of file CPose3D.cpp.
References m_coords, m_pitch, m_roll, m_yaw, mrpt::square(), updateYawPitchRoll(), and mrpt::math::wrapToPi().
Referenced by mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA().
|
inlineinherited |
Returns the Euclidean distance to another pose/point:
Definition at line 214 of file CPoseOrPoint.h.
|
inlineinherited |
Returns the euclidean distance to a 3D point:
Definition at line 249 of file CPoseOrPoint.h.
|
inlineinherited |
Makes a deep copy of the object and returns a smart pointer to it.
Definition at line 204 of file CObject.h.
References mrpt::rtti::CObject::clone().
Referenced by mrpt::obs::CRawlog::insert().
|
inlinestatic |
void CPose3D::fromString | ( | const std::string & | s | ) |
Set the current object value from a string generated by 'asString' (eg: "[x y z yaw pitch roll]", angles in deg.
)
std::exception | On invalid format |
Definition at line 764 of file CPose3D.cpp.
References ASSERTMSG_, mrpt::math::CMatrixDynamic< T >::cols(), mrpt::DEG2RAD(), mrpt::math::MatrixVectorBase< Scalar, Derived >::fromMatlabStringFormat(), mrpt::math::CMatrixDynamic< T >::rows(), setFromValues(), and THROW_EXCEPTION.
Referenced by FromString(), fromStringRaw(), and mrpt::hwdrivers::CKinect::loadConfig_sensorSpecific().
|
inlinestatic |
Definition at line 644 of file CPose3D.h.
References fromString().
Referenced by mrpt::opengl::stock_objects::CornerXYSimple(), mrpt::opengl::stock_objects::CornerXYZSimple(), and TEST().
void CPose3D::fromStringRaw | ( | const std::string & | s | ) |
Same as fromString, but without requiring the square brackets in the string.
Definition at line 776 of file CPose3D.cpp.
References fromString().
|
inline |
Get the pose representation as an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz] where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose.
Definition at line 523 of file CPose3D.h.
References m_coords, and m_ROT.
Referenced by Pose3DTests::check_jacob_LnT_T(), Pose3DTests::func_jacob_Aexpe_D(), Pose3DTests::func_jacob_D_expe(), Pose3DTests::func_jacob_expe_D(), Pose3DTests::func_jacob_expe_e(), and TEST().
void CPose3D::getAsQuaternion | ( | mrpt::math::CQuaternionDouble & | q, |
mrpt::optional_ref< mrpt::math::CMatrixDouble43 > | out_dq_dr = std::nullopt |
||
) | 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). |
Definition at line 501 of file CPose3D.cpp.
References mrpt::math::TPose3D::getAsQuaternion(), m_pitch, m_roll, m_yaw, and updateYawPitchRoll().
Referenced by aux_poseypr2posequat(), check_CPose3D_tofrom_ROS(), mrpt::poses::CPose3DQuatPDFGaussian::copyFrom(), mrpt::poses::CPose3DQuat::CPose3DQuat(), mrpt::poses::CPose3DPDF::jacobiansPoseComposition(), quat_vs_YPR(), TEST_F(), QuaternionTests::test_gimbalLock(), QuaternionTests::test_lnAndExpMatches(), Pose3DQuatTests::test_normalizeJacob(), and mrpt::ros1bridge::toROS_Pose().
|
inlinestatic |
void CPose3D::getHomogeneousMatrix | ( | mrpt::math::CMatrixDouble44 & | out_HM | ) | const |
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).
Definition at line 781 of file CPose3D.cpp.
References mrpt::math::CMatrixFixed< T, ROWS, COLS >::asEigen(), m_coords, and m_ROT.
Referenced by mrpt::maps::CLandmarksMap::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::compute3DMatchingRatio(), mrpt::vision::computeMsd(), mrpt::vision::computeStereoRectificationMaps(), mrpt::vision::CDifodo::filterLevelSolution(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CPointsMap::loadFromVelodyneScan(), and mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan().
|
inlineinherited |
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).
Definition at line 278 of file CPoseOrPoint.h.
|
inlineinherited |
Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose.
Definition at line 290 of file CPoseOrPoint.h.
|
inlineinherited |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Definition at line 298 of file CPoseOrPoint.h.
CPose3D CPose3D::getOppositeScalar | ( | ) | const |
|
inline |
|
inline |
|
inline |
Get the 3x3 rotation matrix.
Definition at line 225 of file CPose3D.h.
References m_ROT.
Referenced by mrpt::poses::CPoint2DPDFGaussian::changeCoordinatesReference(), mrpt::poses::CPointPDFGaussian::changeCoordinatesReference(), mrpt::obs::CObservation3DRangeScan::doDepthAndIntensityCamerasCoincide(), mrpt::vision::frameJac(), Pose3DTests::func_jacob_LnT_T(), jacob_dA_eps_D_p_deps(), mrpt::poses::operator!=(), mrpt::poses::operator==(), quat_vs_YPR(), mrpt::opengl::COpenGLViewport::renderNormalSceneMode(), run_test_so3_avrg(), TEST(), QuaternionTests::test_toYPRAndBack(), and mrpt::ros1bridge::toROS_tfTransform().
|
inline |
|
overridevirtual |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::serialization::CSerializable.
|
static |
void CPose3D::getYawPitchRoll | ( | double & | yaw, |
double & | pitch, | ||
double & | roll | ||
) | const |
Returns the three angles (yaw, pitch, roll), in radians, from the rotation matrix.
Definition at line 304 of file CPose3D.cpp.
References m_ROT, pitch(), roll(), and yaw().
Referenced by updateYawPitchRoll().
|
inlinestatic |
void CPose3D::inverse | ( | ) |
Convert this pose into its inverse, saving the result in itself.
Definition at line 584 of file CPose3D.cpp.
References mrpt::math::homogeneousMatrixInverse(), m_coords, m_ROT, m_ypr_uptodate, and mrpt::math::UNINITIALIZED_MATRIX.
Referenced by Pose3DTests::test_inverse().
Makes this method is slightly more efficient than "this= A - B;" since it avoids the temporary object.
Definition at line 612 of file CPose3D.cpp.
References mrpt::math::homogeneousMatrixInverse(), m_coords, m_ROT, m_ypr_uptodate, and mrpt::math::UNINITIALIZED_MATRIX.
Referenced by operator-().
void mrpt::poses::CPose3D::inverseComposePoint | ( | const double | gx, |
const double | gy, | ||
const double | gz, | ||
double & | lx, | ||
double & | ly, | ||
double & | lz, | ||
mrpt::optional_ref< mrpt::math::CMatrixDouble33 > | out_jacobian_df_dpoint = std::nullopt , |
||
mrpt::optional_ref< mrpt::math::CMatrixDouble36 > | out_jacobian_df_dpose = std::nullopt , |
||
mrpt::optional_ref< mrpt::math::CMatrixDouble36 > | out_jacobian_df_dse3 = std::nullopt |
||
) | const |
Computes the 3D point L such as .
If pointers are provided, the corresponding Jacobians are returned. "out_jacobian_df_dse3" stands for the Jacobian with respect to the 6D locally Euclidean vector in the tangent space of SE(3). See this report for mathematical details.
Referenced by mrpt::vision::frameJac(), mrpt::ros1bridge::fromROS(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), inverseComposePoint(), mrpt::vision::pointJac(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), run_pc_filter_test(), sphericalCoordinates(), TEST(), Pose3DQuatTests::test_invComposePoint_vs_CPose3D(), Pose3DTests::test_invComposePointJacob(), and Pose3DTests::test_invComposePointJacob_se3().
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Definition at line 364 of file CPose3D.h.
References inverseComposePoint(), mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Definition at line 370 of file CPose3D.h.
References inverseComposePoint().
|
inline |
overload for 2D points
If | the z component of the result is greater than some epsilon |
Definition at line 380 of file CPose3D.h.
References ASSERT_BELOW_, eps, inverseComposePoint(), mrpt::math::TPoint2D_data< T >::x, and mrpt::math::TPoint2D_data< T >::y.
mrpt::math::TVector3D CPose3D::inverseRotateVector | ( | const mrpt::math::TVector3D & | global | ) | const |
Inverse of rotateVector(), i.e.
using the inverse rotation matrix
Definition at line 470 of file CPose3D.cpp.
References m_ROT, mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.
|
inlinestaticinherited |
Return true for poses or points with a Z component, false otherwise.
Definition at line 180 of file CPoseOrPoint.h.
|
inlinestatic |
|
inlinestatic |
Definition at line 680 of file CPose3D.h.
References is_PDF_val.
bool 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).
Definition at line 599 of file CPose3D.cpp.
References M_PI, m_pitch, m_roll, updateYawPitchRoll(), and mrpt::math::wrapToPi().
Referenced by mrpt::maps::CPointsMap::internal_computeObservationLikelihood().
|
inlinestatic |
Definition at line 699 of file CPose3D.h.
References static_size.
|
inlineinherited |
Returns the euclidean norm of vector: .
Definition at line 256 of file CPoseOrPoint.h.
void CPose3D::normalizeAngles | ( | ) |
Rebuild the internal matrix & update the yaw/pitch/roll angles within the ]-PI,PI] range (Must be called after using addComponents)
Definition at line 261 of file CPose3D.cpp.
References updateYawPitchRoll().
Referenced by mrpt::hmtslam::CHierarchicalMapMHPartition::getAs3DScene().
void CPose3D::operator*= | ( | const double | s | ) |
Scalar multiplication of x,y,z,yaw,pitch & roll (angles will be wrapped to the ]-pi,pi] interval).
Definition at line 289 of file CPose3D.cpp.
References m_coords, m_pitch, m_roll, m_yaw, rebuildRotationMatrix(), and updateYawPitchRoll().
The operator is the pose compounding operator.
Definition at line 249 of file CPose3D.h.
References composeFrom(), and mrpt::poses::UNINITIALIZED_POSE.
The operator is the pose compounding operator.
Definition at line 531 of file CPose3D.cpp.
References m_coords, m_ROT, mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y().
The operator is the pose compounding operator.
Definition at line 545 of file CPose3D.cpp.
References m_coords, m_ROT, mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y().
Make (b can be "this" without problems)
Definition at line 397 of file CPose3D.h.
References composeFrom().
Compute .
Definition at line 411 of file CPose3D.h.
References inverseComposeFrom(), and mrpt::poses::UNINITIALIZED_POSE.
|
inline |
|
inline |
Get the PITCH angle (in radians)
Definition at line 552 of file CPose3D.h.
References m_pitch, and updateYawPitchRoll().
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::accumulateAngleDiffs(), asTPose(), mrpt::graphs::detail::graph_ops< graph_t >::auxEuclid2Dist(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::checkRegistrationCondition(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::checkRegistrationConditionPose(), mrpt::obs::CActionRobotMovement3D::computeFromOdometry_model6DOF(), CPose3D(), mrpt::poses::CPoseRandomSampler::do_sample_3D(), mrpt::poses::CPose3DPDFGaussianInf::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::poses::CPose3DPDFGaussianInf::drawSingleSample(), mrpt::poses::CPose3DPDFGaussian::drawSingleSample(), mrpt::hmtslam::CHierarchicalMapMHPartition::dumpAsText(), mrpt::hmtslam::CLocalMetricHypothesis::getAs3DScene(), mrpt::opengl::CRenderizable::getPosePitch(), mrpt::opengl::CRenderizable::getPosePitchRad(), getYawPitchRoll(), mrpt::slam::CICP::ICP3D_Method_Classic(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::poses::CPoint3D::operator+(), mrpt::poses::operator<<(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::poses::CPose3DPDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DPDFGaussian::saveToTextFile(), mrpt::tfest::se3_l2_robust(), Pose3DTests::test_default_values(), TEST_F(), mrpt::opengl::CDisk::traceRay(), mrpt::graphs::detail::graph_ops< graph_t >::write_EDGE_line(), and mrpt::graphs::detail::graph_ops< graph_t >::write_VERTEX_line().
|
protected |
Rebuild the homog matrix from the angles.
Definition at line 281 of file CPose3D.cpp.
References m_pitch, m_roll, m_ROT, and m_yaw.
Referenced by addComponents(), operator*=(), and setFromValues().
|
inlinestatic |
Definition at line 700 of file CPose3D.h.
References mrpt::format(), and static_size.
|
inline |
Get the ROLL angle (in radians)
Definition at line 558 of file CPose3D.h.
References m_roll, and updateYawPitchRoll().
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::accumulateAngleDiffs(), asTPose(), mrpt::graphs::detail::graph_ops< graph_t >::auxEuclid2Dist(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::checkRegistrationCondition(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::checkRegistrationConditionPose(), mrpt::obs::CActionRobotMovement3D::computeFromOdometry_model6DOF(), CPose3D(), mrpt::poses::CPoseRandomSampler::do_sample_3D(), mrpt::poses::CPose3DPDFGaussianInf::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::poses::CPose3DPDFGaussianInf::drawSingleSample(), mrpt::poses::CPose3DPDFGaussian::drawSingleSample(), mrpt::hmtslam::CHierarchicalMapMHPartition::dumpAsText(), mrpt::hmtslam::CLocalMetricHypothesis::getAs3DScene(), mrpt::opengl::CRenderizable::getPoseRoll(), mrpt::opengl::CRenderizable::getPoseRollRad(), getYawPitchRoll(), mrpt::slam::CICP::ICP3D_Method_Classic(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::poses::CPoint3D::operator+(), mrpt::poses::operator<<(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::poses::CPose3DPDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DPDFGaussian::saveToTextFile(), mrpt::tfest::se3_l2_robust(), Pose3DTests::test_default_values(), TEST_F(), mrpt::opengl::CDisk::traceRay(), mrpt::graphs::detail::graph_ops< graph_t >::write_EDGE_line(), and mrpt::graphs::detail::graph_ops< graph_t >::write_VERTEX_line().
mrpt::math::TVector3D CPose3D::rotateVector | ( | const mrpt::math::TVector3D & | local | ) | const |
Rotates a vector (i.e.
like composePoint(), but ignoring translation)
Definition at line 460 of file CPose3D.cpp.
References m_ROT, mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.
Referenced by mrpt::opengl::internal::glDrawTextTransformed(), and mrpt::opengl::CArrow::onUpdateBuffers_Triangles().
|
inlineprotectedvirtualinherited |
Virtual method for reading (deserializing) from an abstract schema based archive.
Definition at line 74 of file CSerializable.h.
References mrpt::serialization::CSerializable::GetRuntimeClass(), and THROW_EXCEPTION.
|
overrideprotectedvirtual |
Pure virtual method for reading (deserializing) from an abstract archive.
Users don't call this method directly. Instead, use stream >> object;
.
in | The input binary stream where the object data must read from. |
version | The version of the object stored in the stream: use this version number in your code to know how to read the incoming data. |
std::exception | On any I/O error |
Implements mrpt::serialization::CSerializable.
Definition at line 135 of file CPose3D.cpp.
References ASSERT_, mrpt::math::MatrixVectorBase< Scalar, Derived >::block(), m_coords, m_ROT, m_ypr_uptodate, MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, and mrpt::math::UNINITIALIZED_QUATERNION.
|
overrideprotectedvirtual |
Must return the current versioning number of the object.
Start in zero for new classes, and increments each time there is a change in the stored format.
Implements mrpt::serialization::CSerializable.
Definition at line 123 of file CPose3D.cpp.
|
inlineprotectedvirtualinherited |
Virtual method for writing (serializing) to an abstract schema based archive.
Definition at line 64 of file CSerializable.h.
References mrpt::serialization::CSerializable::GetRuntimeClass(), and THROW_EXCEPTION.
|
overrideprotectedvirtual |
Pure virtual method for writing (serializing) to an abstract archive.
Users don't call this method directly. Instead, use stream << object;
.
std::exception | On any I/O error |
Implements mrpt::serialization::CSerializable.
Definition at line 124 of file CPose3D.cpp.
|
inline |
Set pose from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz] where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose.
Definition at line 499 of file CPose3D.h.
References m_coords, m_ROT, and m_ypr_uptodate.
Referenced by CPose3D(), and Pose3DTests::func_jacob_LnT_T().
void 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 rotation matrix.
Definition at line 265 of file CPose3D.cpp.
References m_coords, m_pitch, m_roll, m_yaw, m_ypr_uptodate, rebuildRotationMatrix(), and mrpt::math::wrapToPi().
Referenced by mrpt::slam::CMetricMapBuilderRBPF::clear(), mrpt::poses::CPose3DPDFGaussian::copyFrom(), CPose3D(), mrpt::poses::CPoseRandomSampler::do_sample_3D(), mrpt::poses::CPoseRandomSampler::drawSample(), mrpt::poses::CPose3DPDFGaussian::drawSingleSample(), fromString(), mrpt::poses::CPose3DPDFSOG::getMean(), mrpt::poses::internal::getPoseFromString(), mrpt::hwdrivers::CIMUXSens_MT4::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUXSens::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSkeletonTracker::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGyroKVHDSP3000::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRoboPeakLidar::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::CHokuyoURG::loadConfig_sensorSpecific(), mrpt::hwdrivers::CKinect::loadConfig_sensorSpecific(), mrpt::topography::path_from_rtk_gps(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), setYawPitchRoll(), and TEST().
|
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 468 of file CPose3D.h.
References ASSERT_ABOVEEQ_, m_coords, m_ROT, and m_ypr_uptodate.
|
inline |
Sets the 3x3 rotation matrix.
Definition at line 237 of file CPose3D.h.
References m_ROT, and m_ypr_uptodate.
Referenced by mrpt::ros1bridge::fromROS(), Pose3DTests::func_jacob_LnT_T(), and mrpt::vision::CStereoRectifyMap::setFromCamParams().
|
overridevirtual |
Set all data fields to quiet NaN.
Implements mrpt::poses::CPoseOrPoint< CPose3D, DIM >.
Definition at line 749 of file CPose3D.cpp.
|
inline |
Set the 3 angles of the 3D pose (in radians) - This method recomputes the internal rotation coordinates matrix.
Definition at line 486 of file CPose3D.h.
References setFromValues(), mrpt::poses::CPoseOrPoint< CPose3D, DIM >::x(), and mrpt::poses::CPoseOrPoint< CPose3D, DIM >::y().
|
inlinestatic |
Definition at line 697 of file CPose3D.h.
References static_size.
Referenced by mrpt::obs::CObservation2DRangeScan::truncateByDistanceAndAngle().
void CPose3D::sphericalCoordinates | ( | const mrpt::math::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.
Definition at line 312 of file CPose3D.cpp.
References inverseComposePoint(), mrpt::math::TPoint3D_< T >::norm(), mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.
Referenced by mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), and Pose3DQuatTests::test_invComposePoint_vs_CPose3D().
|
inlineinherited |
Returns the squared euclidean distance to another pose/point:
Definition at line 187 of file CPoseOrPoint.h.
|
inlineprotected |
Updates Yaw/pitch/roll members from the m_ROT.
Definition at line 116 of file CPose3D.h.
References getYawPitchRoll(), m_pitch, m_roll, m_yaw, and m_ypr_uptodate.
Referenced by addComponents(), asString(), asVector(), distanceEuclidean6D(), getAsQuaternion(), isHorizontal(), normalizeAngles(), operator*=(), operator[](), pitch(), roll(), and yaw().
|
inlinevirtualinherited |
Introduces a pure virtual method responsible for writing to a mxArray
Matlab object, typically a MATLAB struct
whose contents are documented in each derived class.
mxArray
(caller is responsible of memory freeing) or nullptr is class does not support conversion to MATLAB. Definition at line 90 of file CSerializable.h.
|
inlineinherited |
Common members of all points & poses classes.
< Get X coord.
Definition at line 143 of file CPoseOrPoint.h.
Referenced by asTPose(), CPose3D(), and setYawPitchRoll().
|
inlineinherited |
Definition at line 152 of file CPoseOrPoint.h.
|
inlineinherited |
v | Set X coord. |
Definition at line 161 of file CPoseOrPoint.h.
|
inlineinherited |
v | X+=v |
Definition at line 170 of file CPoseOrPoint.h.
|
inlineinherited |
< Get Y coord.
Definition at line 147 of file CPoseOrPoint.h.
Referenced by asTPose(), CPose3D(), and setYawPitchRoll().
|
inlineinherited |
Definition at line 156 of file CPoseOrPoint.h.
|
inlineinherited |
v | Set Y coord. |
Definition at line 165 of file CPoseOrPoint.h.
|
inlineinherited |
v | Y+=v |
Definition at line 174 of file CPoseOrPoint.h.
|
inline |
Get the YAW angle (in radians)
Definition at line 546 of file CPose3D.h.
References m_yaw, and updateYawPitchRoll().
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::accumulateAngleDiffs(), asTPose(), mrpt::graphs::detail::graph_ops< graph_t >::auxEuclid2Dist(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::checkRegistrationCondition(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::checkRegistrationConditionPose(), mrpt::obs::CActionRobotMovement3D::computeFromOdometry_model6DOF(), CPose3D(), mrpt::poses::CPoseRandomSampler::do_sample_3D(), mrpt::poses::CPose3DPDFGaussianInf::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::poses::CPoseRandomSampler::drawSample(), mrpt::poses::CPose3DPDFGaussianInf::drawSingleSample(), mrpt::poses::CPose3DPDFGaussian::drawSingleSample(), mrpt::hmtslam::CHierarchicalMapMHPartition::dumpAsText(), mrpt::hmtslam::CLocalMetricHypothesis::getAs3DScene(), mrpt::opengl::CRenderizable::getPoseYaw(), mrpt::opengl::CRenderizable::getPoseYawRad(), getYawPitchRoll(), mrpt::slam::CICP::ICP3D_Method_Classic(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::poses::CPoint3D::operator+(), mrpt::poses::operator<<(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::processOneLMH(), mrpt::apps::ICP_SLAM_App_Base::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::poses::CPose3DPDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DPDFGaussian::saveToTextFile(), mrpt::tfest::se3_l2_robust(), Pose3DTests::test_default_values(), TEST_F(), Pose3DTests::test_to_from_2d(), mrpt::opengl::CDisk::traceRay(), mrpt::graphs::detail::graph_ops< graph_t >::write_EDGE_line(), and mrpt::graphs::detail::graph_ops< graph_t >::write_VERTEX_line().
|
static |
mrpt::math::CVectorFixedDouble<3> mrpt::poses::CPose3D::m_coords |
The translation vector [x,y,z] access directly or with x(), y(), z() setter/getter methods.
Definition at line 97 of file CPose3D.h.
Referenced by addComponents(), asString(), asVector(), composeFrom(), CPose3D(), distanceEuclidean6D(), getAs12Vector(), getHomogeneousMatrix(), getOppositeScalar(), inverse(), inverseComposeFrom(), mrpt::poses::operator!=(), operator*=(), operator+(), mrpt::poses::operator<<(), mrpt::poses::operator==(), operator[](), serializeFrom(), serializeTo(), setFrom12Vector(), setFromValues(), setFromXYZQ(), and setToNaN().
|
mutableprotected |
Definition at line 110 of file CPose3D.h.
Referenced by addComponents(), asString(), asVector(), distanceEuclidean6D(), getAsQuaternion(), getOppositeScalar(), isHorizontal(), operator*=(), operator[](), pitch(), rebuildRotationMatrix(), setFromValues(), and updateYawPitchRoll().
|
mutableprotected |
Definition at line 110 of file CPose3D.h.
Referenced by addComponents(), asString(), asVector(), distanceEuclidean6D(), getAsQuaternion(), getOppositeScalar(), isHorizontal(), operator*=(), operator[](), rebuildRotationMatrix(), roll(), setFromValues(), and updateYawPitchRoll().
|
protected |
The 3x3 rotation matrix, access with getRotationMatrix(), setRotationMatrix() (It's not safe to set this field as public)
Definition at line 102 of file CPose3D.h.
Referenced by composeFrom(), CPose3D(), getAs12Vector(), getHomogeneousMatrix(), getRotationMatrix(), getYawPitchRoll(), inverse(), inverseComposeFrom(), inverseRotateVector(), operator+(), rebuildRotationMatrix(), rotateVector(), serializeFrom(), serializeTo(), setFrom12Vector(), setFromXYZQ(), setRotationMatrix(), and setToNaN().
|
mutableprotected |
These variables are updated every time that the object rotation matrix is modified (construction, loading from values, pose composition, etc )
Definition at line 110 of file CPose3D.h.
Referenced by addComponents(), asString(), asVector(), distanceEuclidean6D(), getAsQuaternion(), getOppositeScalar(), operator*=(), operator[](), rebuildRotationMatrix(), setFromValues(), updateYawPitchRoll(), and yaw().
|
mutableprotected |
Whether yaw/pitch/roll members are up-to-date since the last rotation matrix update.
Definition at line 106 of file CPose3D.h.
Referenced by composeFrom(), inverse(), inverseComposeFrom(), serializeFrom(), setFrom12Vector(), setFromValues(), setFromXYZQ(), setRotationMatrix(), and updateYawPitchRoll().
|
staticprotected |
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020 |