Public Member Functions | List of all members
RobotDynamics::Math::FramePoint Class Reference

A FramePoint is a 3D point that is expressed in a ReferenceFrame. To change the ReferenceFrame a FramePoint is expressed in, you may call the inhereted FrameObject::changeFrame method and supply it a pointer to the ReferenceFrame you wish to have the FramePoint expressed in. This class and its implementation are an adaptation of FramePoint.java by Jerry Pratt and the IHMC Robotics Group. More...

#include <FramePoint.hpp>

Inheritance diagram for RobotDynamics::Math::FramePoint:
Inheritance graph
[legend]

Public Member Functions

FramePoint changeFrameAndCopy (ReferenceFramePtr referenceFrame) const
 copy into new frame point and change the frame of that More...
 
double distance (const FramePoint &point) const
 Calculate the distance between two FramePoints. $\sqrt{\Delta_x^2+\Delta_y^2+\Delta_z^2}$. More...
 
double distanceL1 (const FramePoint &point) const
 Calculate the L1 distance between two FramePoints by $|\Delta_x| + |\Delta_y| + |\Delta_z|$. More...
 
double distanceLinf (const FramePoint &point) const
 Calculate the LInfinity distance between two FramePoints by $max(|\Delta_x|,|\Delta_y|,|\Delta_z|)$. More...
 
double distanceSquared (const FramePoint &point) const
 Calculate the distance squared between two FramePoints. $\Delta_x^2+\Delta_y^2+\Delta_z^2$. More...
 
bool epsilonEquals (const FramePoint &point, const double epsilon) const
 Return true FramePoint argument is within epsilon of this, false otherwise. More...
 
 FramePoint (ReferenceFramePtr referenceFrame, const double x, const double y, const double z)
 Constructor. More...
 
 FramePoint (ReferenceFramePtr referenceFrame, Math::Vector3d v)
 Constructor. More...
 
 FramePoint (ReferenceFramePtr referenceFrame, const Math::Point3d &point)
 Constructor. More...
 
 FramePoint (const FramePoint &framePoint)
 Copy constructor. More...
 
 FramePoint (ReferenceFramePtr referenceFrame)
 Constructor that initializes to (x,y,z) = (0,0,0) More...
 
 FramePoint ()
 Empty constructor that creates a point with ReferencFrame=nullptr and (x,y,z)=(0,0,0) More...
 
Math::TransformableGeometricObjectgetTransformableGeometricObject ()
 Return a pointer to this as base class type Math::TransformableGeometricObject. See FrameObject::changeFrame for how this method is used. More...
 
template<typename T >
void operator*= (const T scale)
 Overloaded *= operator, performs this = this*scala. More...
 
void operator+= (const FrameVector &v)
 
void operator-= (const FrameVector &v)
 
template<typename T >
void operator/= (const T scale)
 Overloaded /= operator, performs this = this*scale. More...
 
Math::Point3d point () const
 Get as point3d. More...
 
EIGEN_STRONG_INLINE void setIncludingFrame (const Math::Vector3d &v, ReferenceFramePtr referenceFrame)
 Set both the ReferenceFrame this object is expressed in as well as the (x,y,z) coordinates of the point. More...
 
void setIncludingFrame (const double x, const double y, const double z, ReferenceFramePtr referenceFrame)
 Set both the ReferenceFrame the point is expressed in as well as the (x,y,z) coordinates. More...
 
void setIncludingFrame (const Math::Point3d &point, ReferenceFramePtr referenceFrame)
 Set both the ReferenceFrame the point is expressed in as well as the (x,y,z) coordinates. More...
 
 ~FramePoint ()
 Destructor. More...
 
- Public Member Functions inherited from RobotDynamics::FrameObject
virtual void changeFrame (ReferenceFramePtr desiredFrame)
 Change the ReferenceFrame this FrameObject is expressed in. More...
 
void checkReferenceFramesMatch (const FrameObject *frameObject) const
 Check if two ReferenceFrameHolders hold the same ReferenceFrame. More...
 
void checkReferenceFramesMatch (FrameObject *frameObject) const
 
 FrameObject (ReferenceFramePtr referenceFrame)
 
ReferenceFramePtr getReferenceFrame () const
 Get a pointer to the reference frame this FrameObject is expressed in. More...
 
void setReferenceFrame (ReferenceFramePtr frame)
 Set frame objects internal reference frame. More...
 
virtual ~FrameObject ()
 Destructor. More...
 
- Public Member Functions inherited from RobotDynamics::Math::Point3d
void absoluteValue ()
 Set each element to the absolute value. More...
 
void clampMax (const double max)
 clamp any values that are greater than make to max More...
 
void clampMin (const double min)
 clamp any values that are less than min to min More...
 
void clampMinMax (const double min, const double max)
 clamp any values greater than max to max, and any value less than min to min More...
 
Vector3d cross (const Vector3d &v)
 Cross product between a point and vector. More...
 
EIGEN_STRONG_INLINE double * data ()
 
double distance (const Point3d &point) const
 
double distanceL1 (const Point3d &point) const
 L1 norm of two points. More...
 
double distanceLinf (const Point3d &point) const
 
double distanceSquared (const Point3d &point) const
 Square of the distance between two ponts, $ x^2 + y^2 + z^2 $. More...
 
EIGEN_STRONG_INLINE bool epsilonEquals (const Point3d &point, const double epsilon) const
 
bool operator!= (const Point3d &rhs)
 
template<typename T >
void operator*= (const T scale)
 
void operator+= (const Vector3d &v)
 
void operator-= (const Vector3d &v)
 
template<typename T >
void operator/= (const T scale)
 
Point3doperator= (const Point3d &other)
 
bool operator== (const Point3d &rhs)
 
 Point3d (const double x, const double y, const double z)
 
 Point3d (const Point3d &point)
 
 Point3d (const Vector3d &vector)
 
EIGEN_STRONG_INLINE Point3d ()
 
EIGEN_STRONG_INLINE void set (const std::vector< double > &vector)
 
EIGEN_STRONG_INLINE void set (const Point3d &point)
 
void set (const Math::Vector3d &v)
 
void set (const double x, const double y, const double z)
 
EIGEN_STRONG_INLINE void setToZero ()
 
void transform (const Math::SpatialTransform &X)
 Performs in place point transform. Given a point, $p$, this performs $ p = -X.E X.r + X.E p $. More...
 
Point3d transform_copy (const Math::SpatialTransform &X)
 
EIGEN_STRONG_INLINE Math::Vector3d vec () const
 
EIGEN_STRONG_INLINE double & x ()
 
EIGEN_STRONG_INLINE double x () const
 
EIGEN_STRONG_INLINE double & y ()
 
EIGEN_STRONG_INLINE double y () const
 
EIGEN_STRONG_INLINE double & z ()
 
EIGEN_STRONG_INLINE double z () const
 
virtual ~Point3d ()
 

Additional Inherited Members

- Protected Attributes inherited from RobotDynamics::FrameObject
ReferenceFramePtr referenceFrame
 
- Protected Attributes inherited from RobotDynamics::Math::Point3d
double point [3]
 

Detailed Description

A FramePoint is a 3D point that is expressed in a ReferenceFrame. To change the ReferenceFrame a FramePoint is expressed in, you may call the inhereted FrameObject::changeFrame method and supply it a pointer to the ReferenceFrame you wish to have the FramePoint expressed in. This class and its implementation are an adaptation of FramePoint.java by Jerry Pratt and the IHMC Robotics Group.

Definition at line 40 of file FramePoint.hpp.

Constructor & Destructor Documentation

RobotDynamics::Math::FramePoint::FramePoint ( ReferenceFramePtr  referenceFrame,
const double  x,
const double  y,
const double  z 
)
inline

Constructor.

Parameters
referenceFrameA pointer to the ReferenceFrame the point will be expressed in
xThe x-component of the point
yThe y-component of the point
zThe z-component of the point

Definition at line 50 of file FramePoint.hpp.

RobotDynamics::Math::FramePoint::FramePoint ( ReferenceFramePtr  referenceFrame,
Math::Vector3d  v 
)
inline

Constructor.

Parameters
referenceFrameA pointer to the ReferenceFrame the point will be expressed in
vA Vector3d that will be used to set the components of this FramePoint

Definition at line 59 of file FramePoint.hpp.

RobotDynamics::Math::FramePoint::FramePoint ( ReferenceFramePtr  referenceFrame,
const Math::Point3d point 
)
inline

Constructor.

Parameters
referenceFrameA pointer to the ReferenceFrame the point will be expressed in
pointA Math::Point3 that will be used to set the components of this FramePoint

Definition at line 68 of file FramePoint.hpp.

RobotDynamics::Math::FramePoint::FramePoint ( const FramePoint framePoint)
inline

Copy constructor.

Parameters
framePointA FramePoint to copy

Definition at line 76 of file FramePoint.hpp.

RobotDynamics::Math::FramePoint::FramePoint ( ReferenceFramePtr  referenceFrame)
inlineexplicit

Constructor that initializes to (x,y,z) = (0,0,0)

Parameters
referenceFrameA pointer to the ReferenceFrame the point will be expressed in

Definition at line 84 of file FramePoint.hpp.

RobotDynamics::Math::FramePoint::FramePoint ( )
inline

Empty constructor that creates a point with ReferencFrame=nullptr and (x,y,z)=(0,0,0)

Definition at line 91 of file FramePoint.hpp.

RobotDynamics::Math::FramePoint::~FramePoint ( )
inline

Destructor.

Definition at line 98 of file FramePoint.hpp.

Member Function Documentation

FramePoint RobotDynamics::Math::FramePoint::changeFrameAndCopy ( ReferenceFramePtr  referenceFrame) const
inline

copy into new frame point and change the frame of that

Parameters
referenceFrame
Returns

Definition at line 126 of file FramePoint.hpp.

double RobotDynamics::Math::FramePoint::distance ( const FramePoint point) const
inline

Calculate the distance between two FramePoints. $\sqrt{\Delta_x^2+\Delta_y^2+\Delta_z^2}$.

Exceptions
ReferenceFrameExceptionIf both points are not expressed in the same ReferenceFrame
Parameters
pointFramePoint to calculate distance to
Returns
Distance between points as template type T

Definition at line 201 of file FramePoint.hpp.

double RobotDynamics::Math::FramePoint::distanceL1 ( const FramePoint point) const
inline

Calculate the L1 distance between two FramePoints by $|\Delta_x| + |\Delta_y| + |\Delta_z|$.

Exceptions
ReferenceFrameExceptionIf both points are not expressed in the same ReferenceFrame
Parameters
pointFramePoint to calculate distance to
Returns
Distance between points as template type T

Definition at line 214 of file FramePoint.hpp.

double RobotDynamics::Math::FramePoint::distanceLinf ( const FramePoint point) const
inline

Calculate the LInfinity distance between two FramePoints by $max(|\Delta_x|,|\Delta_y|,|\Delta_z|)$.

Exceptions
ReferenceFrameExceptionIf both points are not expressed in the same ReferenceFrame
Parameters
pointFramePoint to calculate distance to
Returns
Distance between points as template type T

Definition at line 227 of file FramePoint.hpp.

double RobotDynamics::Math::FramePoint::distanceSquared ( const FramePoint point) const
inline

Calculate the distance squared between two FramePoints. $\Delta_x^2+\Delta_y^2+\Delta_z^2$.

Exceptions
ReferenceFrameExceptionIf both points are not expressed in the same ReferenceFrame
Parameters
pointFramePoint to calculate squared distance to
Returns
Distance squared

Definition at line 185 of file FramePoint.hpp.

bool RobotDynamics::Math::FramePoint::epsilonEquals ( const FramePoint point,
const double  epsilon 
) const
inline

Return true FramePoint argument is within epsilon of this, false otherwise.

Parameters
pointThe FramePoint to be compared
epsilonThe tolerance of the comparison check
Exceptions
ReferenceFrameExceptionIf both points are not expressed in the same ReferenceFrame

Definition at line 246 of file FramePoint.hpp.

Math::TransformableGeometricObject* RobotDynamics::Math::FramePoint::getTransformableGeometricObject ( )
inlinevirtual

Return a pointer to this as base class type Math::TransformableGeometricObject. See FrameObject::changeFrame for how this method is used.

Returns
Pointer to this object as type Math::TransformableGeometricObject

Implements RobotDynamics::FrameObject.

Definition at line 116 of file FramePoint.hpp.

template<typename T >
void RobotDynamics::Math::FramePoint::operator*= ( const T  scale)
inline

Overloaded *= operator, performs this = this*scala.

Parameters
scaleScalar to scale each element of this FramePoint by
Returns
FramePoint representing this = this*scale

Definition at line 258 of file FramePoint.hpp.

void RobotDynamics::Math::FramePoint::operator+= ( const FrameVector v)
inline

Definition at line 278 of file FramePoint.hpp.

void RobotDynamics::Math::FramePoint::operator-= ( const FrameVector v)
inline

Definition at line 286 of file FramePoint.hpp.

template<typename T >
void RobotDynamics::Math::FramePoint::operator/= ( const T  scale)
inline

Overloaded /= operator, performs this = this*scale.

Parameters
scaleScalar to divide each element of this FramePoint by
Returns
FramePoint representing this = this/scale

Definition at line 271 of file FramePoint.hpp.

Math::Point3d RobotDynamics::Math::FramePoint::point ( ) const
inline

Get as point3d.

Returns
Point as Point3d type

Definition at line 106 of file FramePoint.hpp.

EIGEN_STRONG_INLINE void RobotDynamics::Math::FramePoint::setIncludingFrame ( const Math::Vector3d v,
ReferenceFramePtr  referenceFrame 
)
inline

Set both the ReferenceFrame this object is expressed in as well as the (x,y,z) coordinates of the point.

Parameters
vVector3d that this point will be set to
referenceFramePointer to the ReferenceFrame this object will be expressed in

Definition at line 138 of file FramePoint.hpp.

void RobotDynamics::Math::FramePoint::setIncludingFrame ( const double  x,
const double  y,
const double  z,
ReferenceFramePtr  referenceFrame 
)
inline

Set both the ReferenceFrame the point is expressed in as well as the (x,y,z) coordinates.

Parameters
xThe x coordinate
yThe y coordinate
zThe z coordinate
referenceFrameThe ReferenceFrame this point is to be expressed in

Definition at line 150 of file FramePoint.hpp.

void RobotDynamics::Math::FramePoint::setIncludingFrame ( const Math::Point3d point,
ReferenceFramePtr  referenceFrame 
)
inline

Set both the ReferenceFrame the point is expressed in as well as the (x,y,z) coordinates.

Parameters
pointMath::Point3d to set this point to
referenceFramePointer to ReferenceFrame this point will be expressed in

Definition at line 166 of file FramePoint.hpp.


The documentation for this class was generated from the following file:


rdl_dynamics
Author(s):
autogenerated on Tue Apr 20 2021 02:25:28