MRPT  2.0.0
List of all members | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes
mrpt::math::TPose2D Struct Reference

Detailed Description

Lightweight 2D pose.

Allows coordinate access using [] operator.

See also
mrpt::poses::CPose2D

Definition at line 22 of file TPose2D.h.

#include <mrpt/math/TPose2D.h>

Inheritance diagram for mrpt::math::TPose2D:

Public Types

enum  { static_size = 3 }
 

Public Member Functions

 TPose2D (const TPoint2D &p)
 Implicit constructor from TPoint2D. More...
 
 TPose2D (const TPoint3D &p)
 Constructor from TPoint3D, losing information. More...
 
 TPose2D (const TPose3D &p)
 Constructor from TPose3D, losing information. More...
 
constexpr TPose2D (double xx, double yy, double Phi)
 Constructor from coordinates. More...
 
constexpr TPose2D ()=default
 Default fast constructor. More...
 
double & operator[] (size_t i)
 Coordinate access using operator[]. More...
 
constexpr double operator[] (size_t i) const
 Coordinate access using operator[]. More...
 
void asVector (std::vector< double > &v) const
 Transformation into vector. More...
 
void asString (std::string &s) const
 Returns a human-readable textual representation of the object (eg: "[x y yaw]", yaw in degrees) More...
 
std::string asString () const
 
mrpt::math::TPose2D operator+ (const mrpt::math::TPose2D &b) const
 Operator "oplus" pose composition: "ret=this \oplus b". More...
 
mrpt::math::TPose2D operator- (const mrpt::math::TPose2D &b) const
 Operator "ominus" pose composition: "ret=this \ominus b". More...
 
mrpt::math::TPoint2D composePoint (const TPoint2D l) const
 
mrpt::math::TPoint2D operator+ (const mrpt::math::TPoint2D &b) const
 
mrpt::math::TPoint2D inverseComposePoint (const TPoint2D g) const
 
double norm () const
 Returns the norm of the (x,y) vector (phi is not used) More...
 
void normalizePhi ()
 Forces "phi" to be in the range [-pi,pi]. More...
 
void fromString (const std::string &s)
 Set the current object value from a string generated by 'asString' (eg: "[0.02 1.04 -45.0]" ) More...
 
constexpr std::size_t rows () const
 
constexpr std::size_t cols () const
 
constexpr std::size_t size () const
 
void resize (std::size_t n)
 throws if attempted to resize to incorrect length More...
 

Static Public Member Functions

static constexpr TPose2D Identity ()
 Returns the identity transformation. More...
 
static TPose2D FromString (const std::string &s)
 

Public Attributes

double x {.0}
 X,Y coordinates. More...
 
double y {.0}
 
double phi {.0}
 Orientation (rads) More...
 

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
static_size 

Definition at line 25 of file TPose2D.h.

Constructor & Destructor Documentation

◆ TPose2D() [1/5]

TPose2D::TPose2D ( const TPoint2D p)

Implicit constructor from TPoint2D.

Zeroes the phi coordinate.

See also
TPoint2D

Definition at line 21 of file TPose2D.cpp.

◆ TPose2D() [2/5]

TPose2D::TPose2D ( const TPoint3D p)
explicit

Constructor from TPoint3D, losing information.

Zeroes the phi coordinate.

See also
TPoint3D

Definition at line 22 of file TPose2D.cpp.

◆ TPose2D() [3/5]

TPose2D::TPose2D ( const TPose3D p)
explicit

Constructor from TPose3D, losing information.

The phi corresponds to the original pose's yaw.

See also
TPose3D

Definition at line 23 of file TPose2D.cpp.

◆ TPose2D() [4/5]

constexpr mrpt::math::TPose2D::TPose2D ( double  xx,
double  yy,
double  Phi 
)
inline

Constructor from coordinates.

Definition at line 56 of file TPose2D.h.

◆ TPose2D() [5/5]

constexpr mrpt::math::TPose2D::TPose2D ( )
default

Default fast constructor.

Initializes to zeros.

Referenced by Identity().

Here is the caller graph for this function:

Member Function Documentation

◆ asString() [1/2]

void TPose2D::asString ( std::string &  s) const

Returns a human-readable textual representation of the object (eg: "[x y yaw]", yaw in degrees)

See also
fromString

Definition at line 24 of file TPose2D.cpp.

References mrpt::format(), phi, mrpt::RAD2DEG(), x, and y.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), and mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ asString() [2/2]

std::string mrpt::math::TPose2D::asString ( ) const
inline

Definition at line 108 of file TPose2D.h.

◆ asVector()

void mrpt::math::TPose2D::asVector ( std::vector< double > &  v) const
inline

Transformation into vector.

Definition at line 96 of file TPose2D.h.

References phi, x, and y.

◆ cols()

constexpr std::size_t mrpt::math::internal::ProvideStaticResize< TPose2D >::cols ( ) const
inlineinherited

Definition at line 66 of file TPoseOrPoint.h.

◆ composePoint()

TPoint2D TPose2D::composePoint ( const TPoint2D  l) const

Definition at line 64 of file TPose2D.cpp.

References phi, mrpt::math::TPoint2D_data< T >::x, x, mrpt::math::TPoint2D_data< T >::y, and y.

Referenced by mrpt::math::TPolygon2D::createRegularPolygon(), operator+(), and mrpt::math::project2D().

Here is the caller graph for this function:

◆ fromString()

void TPose2D::fromString ( const std::string &  s)

Set the current object value from a string generated by 'asString' (eg: "[0.02 1.04 -45.0]" )

See also
asString
Exceptions
std::exceptionOn invalid format

Definition at line 28 of file TPose2D.cpp.

References ASSERTMSG_, mrpt::math::CMatrixDynamic< T >::cols(), mrpt::DEG2RAD(), mrpt::math::MatrixVectorBase< Scalar, Derived >::fromMatlabStringFormat(), phi, mrpt::math::CMatrixDynamic< T >::rows(), THROW_EXCEPTION, x, and y.

Referenced by FromString(), and TEST().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ FromString()

static TPose2D mrpt::math::TPose2D::FromString ( const std::string &  s)
inlinestatic

Definition at line 136 of file TPose2D.h.

References fromString().

Here is the call graph for this function:

◆ Identity()

static constexpr TPose2D mrpt::math::TPose2D::Identity ( )
inlinestatic

Returns the identity transformation.

Definition at line 35 of file TPose2D.h.

References TPose2D().

Here is the call graph for this function:

◆ inverseComposePoint()

mrpt::math::TPoint2D TPose2D::inverseComposePoint ( const TPoint2D  g) const

Definition at line 74 of file TPose2D.cpp.

References phi, mrpt::math::TPoint2D_data< T >::x, x, mrpt::math::TPoint2D_data< T >::y, and y.

Referenced by mrpt::nav::CReactiveNavigationSystem::checkCollisionWithLatestObstacles(), mrpt::nav::CReactiveNavigationSystem3D::checkCollisionWithLatestObstacles(), and mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle().

Here is the caller graph for this function:

◆ norm()

double mrpt::math::TPose2D::norm ( ) const
inline

Returns the norm of the (x,y) vector (phi is not used)

Definition at line 127 of file TPose2D.h.

References mrpt::hypot_fast(), x, and y.

Here is the call graph for this function:

◆ normalizePhi()

void mrpt::math::TPose2D::normalizePhi ( )
inline

Forces "phi" to be in the range [-pi,pi].

Definition at line 129 of file TPose2D.h.

References phi, and mrpt::math::wrapToPi().

Here is the call graph for this function:

◆ operator+() [1/2]

mrpt::math::TPose2D mrpt::math::TPose2D::operator+ ( const mrpt::math::TPose2D b) const

Operator "oplus" pose composition: "ret=this \oplus b".

See also
CPose2D

Definition at line 39 of file TPose2D.cpp.

References phi, mrpt::math::wrapToPi(), x, and y.

Here is the call graph for this function:

◆ operator+() [2/2]

mrpt::math::TPoint2D TPose2D::operator+ ( const mrpt::math::TPoint2D b) const

Definition at line 69 of file TPose2D.cpp.

References composePoint().

Here is the call graph for this function:

◆ operator-()

mrpt::math::TPose2D mrpt::math::TPose2D::operator- ( const mrpt::math::TPose2D b) const

Operator "ominus" pose composition: "ret=this \ominus b".

See also
CPose2D

Definition at line 51 of file TPose2D.cpp.

References phi, mrpt::math::wrapToPi(), x, and y.

Here is the call graph for this function:

◆ operator[]() [1/2]

double& mrpt::math::TPose2D::operator[] ( size_t  i)
inline

Coordinate access using operator[].

Order: x,y,phi

Definition at line 64 of file TPose2D.h.

References phi, x, and y.

◆ operator[]() [2/2]

constexpr double mrpt::math::TPose2D::operator[] ( size_t  i) const
inline

Coordinate access using operator[].

Order: x,y,phi

Definition at line 79 of file TPose2D.h.

References phi, x, and y.

◆ resize()

void mrpt::math::internal::ProvideStaticResize< TPose2D >::resize ( std::size_t  n)
inlineinherited

throws if attempted to resize to incorrect length

Definition at line 70 of file TPoseOrPoint.h.

◆ rows()

constexpr std::size_t mrpt::math::internal::ProvideStaticResize< TPose2D >::rows ( ) const
inlineinherited

Definition at line 65 of file TPoseOrPoint.h.

◆ size()

constexpr std::size_t mrpt::math::internal::ProvideStaticResize< TPose2D >::size ( ) const
inlineinherited

Definition at line 67 of file TPoseOrPoint.h.

Member Data Documentation

◆ phi

double mrpt::math::TPose2D::phi {.0}

Orientation (rads)

Definition at line 32 of file TPose2D.h.

Referenced by asString(), asVector(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::obs::carmen_log_parse_line(), composePoint(), mrpt::math::createFromPoseAndVector(), mrpt::math::createFromPoseX(), mrpt::math::createFromPoseY(), mrpt::nav::CParameterizedTrajectoryGenerator::debugDumpInFiles(), mrpt::maps::COccupancyGridMap2D::determineMatching2D(), mrpt::nav::PoseDistanceMetric< TNodeSE2 >::distance(), mrpt::poses::CRobot2DPoseEstimator::extrapolateRobotPose(), fromString(), mrpt::math::TLine2D::getAsPose2D(), mrpt::math::TLine2D::getAsPose2DForcingOrigin(), mrpt::poses::CRobot2DPoseEstimator::getCurrentEstimate(), mrpt::kinematics::CVehicleSimulVirtualBase::getCurrentGTVelLocal(), mrpt::kinematics::CVehicleSimulVirtualBase::getCurrentOdometricVelLocal(), mrpt::poses::CRobot2DPoseEstimator::getLatestRobotPose(), mrpt::nav::CPTG_Holo_Blend::getPathPose(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::getPathPose(), mrpt::hwdrivers::CRovio::getPosition(), mrpt::slam::CICP::ICP_Method_Classic(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize(), mrpt::kinematics::CVehicleSimul_Holo::internal_simulControlStep(), mrpt::kinematics::CVehicleSimul_DiffDriven::internal_simulControlStep(), inverseComposePoint(), mrpt::slam::KLF_loadBinFromParticle(), mrpt::graphs::detail::graph_ops< graph_t >::load_graph_of_poses_from_text_stream(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), normalizePhi(), mrpt::math::operator!=(), operator+(), operator-(), mrpt::math::operator==(), operator[](), mrpt::math::project2D(), mrpt::poses::CPosePDFParticles::resetAroundSetOfPoses(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), mrpt::tfest::se2_l2(), mrpt::kinematics::CVehicleSimul_Holo::sendVelCmd(), mrpt::poses::CPosePDFGaussianInf::serializeFrom(), mrpt::kinematics::CVehicleSimulVirtualBase::simulateOneTimeStep(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), TEST(), mrpt::ros1bridge::toROS_Pose(), mrpt::nav::CAbstractNavigator::updateCurrentPoseAndSpeeds(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().

◆ x

double mrpt::math::TPose2D::x {.0}

X,Y coordinates.

Definition at line 30 of file TPose2D.h.

Referenced by asString(), asVector(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::PoseDistanceMetric< TNodeSE2 >::cannotBeNearerThan(), mrpt::nav::PoseDistanceMetric< TNodeSE2_TP >::cannotBeNearerThan(), mrpt::obs::carmen_log_parse_line(), composePoint(), mrpt::poses::CPose2D::CPose2D(), mrpt::math::createFromPoseAndVector(), mrpt::math::createFromPoseX(), mrpt::math::createFromPoseY(), mrpt::nav::CParameterizedTrajectoryGenerator::debugDumpInFiles(), mrpt::maps::COccupancyGridMap2D::determineMatching2D(), mrpt::nav::PoseDistanceMetric< TNodeSE2 >::distance(), mrpt::poses::CRobot2DPoseEstimator::extrapolateRobotPose(), fromString(), mrpt::math::TLine2D::getAsPose2D(), mrpt::poses::CRobot2DPoseEstimator::getLatestRobotPose(), mrpt::nav::CPTG_Holo_Blend::getPathPose(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::getPathPose(), mrpt::hwdrivers::CRovio::getPosition(), mrpt::hwdrivers::CRovio::getRovioState(), mrpt::slam::CICP::ICP_Method_Classic(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize(), inverseComposePoint(), mrpt::slam::KLF_loadBinFromParticle(), mrpt::graphs::detail::graph_ops< graph_t >::load_graph_of_poses_from_text_stream(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), norm(), mrpt::math::operator!=(), operator+(), operator-(), mrpt::math::operator==(), operator[](), mrpt::math::project2D(), mrpt::nav::CParameterizedTrajectoryGenerator::renderPathAsSimpleLine(), mrpt::poses::CPosePDFParticles::resetAroundSetOfPoses(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), mrpt::tfest::se2_l2(), mrpt::poses::CPosePDFGaussianInf::serializeFrom(), mrpt::kinematics::CVehicleSimulVirtualBase::simulateOneTimeStep(), TEST(), mrpt::ros1bridge::toROS_Pose(), mrpt::math::TPoint2D_< double >::TPoint2D_(), mrpt::math::TPoint3D_< float >::TPoint3D_(), mrpt::nav::CParameterizedTrajectoryGenerator::updateNavDynamicState(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().

◆ y

double mrpt::math::TPose2D::y {.0}

Definition at line 30 of file TPose2D.h.

Referenced by asString(), asVector(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::PoseDistanceMetric< TNodeSE2 >::cannotBeNearerThan(), mrpt::nav::PoseDistanceMetric< TNodeSE2_TP >::cannotBeNearerThan(), mrpt::obs::carmen_log_parse_line(), composePoint(), mrpt::poses::CPose2D::CPose2D(), mrpt::math::createFromPoseAndVector(), mrpt::math::createFromPoseX(), mrpt::math::createFromPoseY(), mrpt::nav::CParameterizedTrajectoryGenerator::debugDumpInFiles(), mrpt::maps::COccupancyGridMap2D::determineMatching2D(), mrpt::nav::PoseDistanceMetric< TNodeSE2 >::distance(), mrpt::poses::CRobot2DPoseEstimator::extrapolateRobotPose(), fromString(), mrpt::math::TLine2D::getAsPose2D(), mrpt::poses::CRobot2DPoseEstimator::getLatestRobotPose(), mrpt::nav::CPTG_Holo_Blend::getPathPose(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::getPathPose(), mrpt::hwdrivers::CRovio::getPosition(), mrpt::slam::CICP::ICP_Method_Classic(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize(), inverseComposePoint(), mrpt::slam::KLF_loadBinFromParticle(), mrpt::graphs::detail::graph_ops< graph_t >::load_graph_of_poses_from_text_stream(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), norm(), mrpt::math::operator!=(), operator+(), operator-(), mrpt::math::operator==(), operator[](), mrpt::math::project2D(), mrpt::nav::CParameterizedTrajectoryGenerator::renderPathAsSimpleLine(), mrpt::poses::CPosePDFParticles::resetAroundSetOfPoses(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), mrpt::tfest::se2_l2(), mrpt::poses::CPosePDFGaussianInf::serializeFrom(), TEST(), mrpt::ros1bridge::toROS_Pose(), mrpt::math::TPoint2D_< double >::TPoint2D_(), mrpt::math::TPoint3D_< float >::TPoint3D_(), mrpt::nav::CParameterizedTrajectoryGenerator::updateNavDynamicState(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().




Page generated by Doxygen 1.8.14 for MRPT 2.0.0 Git: b38439d21 Tue Mar 31 19:58:06 2020 +0200 at miƩ abr 1 00:50:30 CEST 2020