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

A FrameVector is a 3D vector with a ReferenceFrame, and all operations between FrameVectors and other frame objects will perform runtime checks that objects are expressed in the same frames. This class and its implementation are an adaptation of FrameVector.java by Jerry Pratt and the IHMC Robotics Group. More...

#include <FrameVector.hpp>

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

Public Member Functions

FrameVector changeFrameAndCopy (ReferenceFramePtr referenceFrame) const
 copy into new frame vector and change the frame of that More...
 
FrameVector cross (const FrameVector &vector) const
 Cross product between two FrameVectors, i.e. $ v_1 \times v_2 $. More...
 
Vector3d cross (const Vector3d &vector) const
 Cross product, i.e. $ v_1 \times v_2 $. More...
 
double dot (const FrameVector &frameVector) const
 Dot product between two FrameVectors, i.e. $ v_1 \cdot v_2 $. More...
 
 FrameVector ()
 Default constructor. Initializes its ReferenceFrame to nullptr. More...
 
 FrameVector (ReferenceFramePtr referenceFrame)
 Constructor. More...
 
 FrameVector (ReferenceFramePtr referenceFrame, const double &x, const double &y, const double &z)
 Constructor. More...
 
 FrameVector (ReferenceFramePtr referenceFrame, const Eigen::Vector3d &vector)
 Constructor. More...
 
double getAngleBetweenVectors (const FrameVector &frameVector) const
 Computer the angle between two FrameVectors, $ \arccos{\frac{v_1 \cdot v_2}{|v_1||v_2|}} $. More...
 
Math::TransformableGeometricObjectgetTransformableGeometricObject ()
 Return pointer to this object as type TransformableGeometricObject. See FrameObject::changeFrame for an example of where this method is used. More...
 
template<typename T >
void operator*= (const T scale)
 Times euals operator that performs runtime frame checks, $ v=v*scale $. More...
 
void operator+= (const Vector3d &v)
 
void operator+= (const FrameVector &v)
 Plus euals operator that performs runtime frame checks, $ v_1=v_1-v $. More...
 
void operator-= (const Vector3d &v)
 
void operator-= (const FrameVector &v)
 Minus euals operator that performs runtime frame checks, $ v_1=v_1-v $. More...
 
void setIncludingFrame (const double x, const double y, const double z, ReferenceFramePtr referenceFrame)
 Set the x, y, and z components and the ReferenceFrame these components are expressed in. More...
 
void setIncludingFrame (const Eigen::Vector3d &vector, ReferenceFramePtr referenceFrame)
 Set the x, y, and z components and the ReferenceFrame these components are expressed in. More...
 
void setToZero ()
 Set x, y, and z components to 0. More...
 
Vector3d vec () const
 
virtual ~FrameVector ()
 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::Vector3d
template<typename OtherDerived >
Vector3doperator= (const Eigen::MatrixBase< OtherDerived > &other)
 
void set (const Eigen::Vector3d &v)
 
void set (const double &v0, const double &v1, const double &v2)
 
void transform (const RobotDynamics::Math::SpatialTransform &X)
 Pure virtual object. This object forces objects that inherit from it to have a method that tells how that object is transformed. More...
 
Vector3d transform_copy (const RobotDynamics::Math::SpatialTransform &X) const
 
template<typename OtherDerived >
 Vector3d (const Eigen::MatrixBase< OtherDerived > &other)
 
EIGEN_STRONG_INLINE Vector3d ()
 
EIGEN_STRONG_INLINE Vector3d (const double &v0, const double &v1, const double &v2)
 

Additional Inherited Members

- Public Types inherited from RobotDynamics::Math::Vector3d
typedef Eigen::Vector3d Base
 
- Protected Attributes inherited from RobotDynamics::FrameObject
ReferenceFramePtr referenceFrame
 

Detailed Description

A FrameVector is a 3D vector with a ReferenceFrame, and all operations between FrameVectors and other frame objects will perform runtime checks that objects are expressed in the same frames. This class and its implementation are an adaptation of FrameVector.java by Jerry Pratt and the IHMC Robotics Group.

Definition at line 33 of file FrameVector.hpp.

Constructor & Destructor Documentation

RobotDynamics::Math::FrameVector::FrameVector ( )
inline

Default constructor. Initializes its ReferenceFrame to nullptr.

Definition at line 39 of file FrameVector.hpp.

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

Constructor.

Parameters
referenceFrameA pointer to a ReferenceFrame

Definition at line 47 of file FrameVector.hpp.

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

Constructor.

Parameters
referenceFrameA pointer to a ReferenceFrame
xValue of the x-coordinate
yValue of the y-coordinate
zValue of the z-coordinate

Definition at line 58 of file FrameVector.hpp.

RobotDynamics::Math::FrameVector::FrameVector ( ReferenceFramePtr  referenceFrame,
const Eigen::Vector3d &  vector 
)
inline

Constructor.

Parameters
referenceFramePointer to a ReferenceFrame
vectorA Vector3d used to set the x,y, and z coordinates

Definition at line 67 of file FrameVector.hpp.

virtual RobotDynamics::Math::FrameVector::~FrameVector ( )
inlinevirtual

Destructor.

Definition at line 74 of file FrameVector.hpp.

Member Function Documentation

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

copy into new frame vector and change the frame of that

Parameters
referenceFrame
Returns

Definition at line 93 of file FrameVector.hpp.

FrameVector RobotDynamics::Math::FrameVector::cross ( const FrameVector vector) const
inline

Cross product between two FrameVectors, i.e. $ v_1 \times v_2 $.

Parameters
vector
Exceptions
ReferenceFrameExceptionIf the FrameVectors aren't expressed in the same ReferenceFrame
Returns
The cross product

Definition at line 163 of file FrameVector.hpp.

Vector3d RobotDynamics::Math::FrameVector::cross ( const Vector3d vector) const
inline

Cross product, i.e. $ v_1 \times v_2 $.

Parameters
vector
Returns
The cross product

Definition at line 175 of file FrameVector.hpp.

double RobotDynamics::Math::FrameVector::dot ( const FrameVector frameVector) const
inline

Dot product between two FrameVectors, i.e. $ v_1 \cdot v_2 $.

Parameters
frameVector
Exceptions
ReferenceFrameExceptionIf the FrameVectors aren't expressed in the same ReferenceFrame
Returns
The dot product

Definition at line 150 of file FrameVector.hpp.

double RobotDynamics::Math::FrameVector::getAngleBetweenVectors ( const FrameVector frameVector) const
inline

Computer the angle between two FrameVectors, $ \arccos{\frac{v_1 \cdot v_2}{|v_1||v_2|}} $.

Parameters
frameVector
Returns
The angle between the vectors

Definition at line 185 of file FrameVector.hpp.

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

Return pointer to this object as type TransformableGeometricObject. See FrameObject::changeFrame for an example of where this method is used.

Returns
Pointer to this object as type TransformableGeometricObject

Implements RobotDynamics::FrameObject.

Definition at line 83 of file FrameVector.hpp.

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

Times euals operator that performs runtime frame checks, $ v=v*scale $.

Template Parameters
typenameof the scale parameter
Parameters
scale

Definition at line 241 of file FrameVector.hpp.

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

Definition at line 197 of file FrameVector.hpp.

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

Plus euals operator that performs runtime frame checks, $ v_1=v_1-v $.

Parameters
v

Definition at line 215 of file FrameVector.hpp.

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

Definition at line 204 of file FrameVector.hpp.

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

Minus euals operator that performs runtime frame checks, $ v_1=v_1-v $.

Parameters
v

Definition at line 227 of file FrameVector.hpp.

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

Set the x, y, and z components and the ReferenceFrame these components are expressed in.

Parameters
xThe x-component
yy-component
zz-component
Exceptions
ReferenceFrameExceptionIf *referenceFrame=nullptr
Parameters
referenceFramePointer to a ReferenceFrame this point is expressed in

Definition at line 116 of file FrameVector.hpp.

void RobotDynamics::Math::FrameVector::setIncludingFrame ( const Eigen::Vector3d &  vector,
ReferenceFramePtr  referenceFrame 
)
inline

Set the x, y, and z components and the ReferenceFrame these components are expressed in.

Parameters
vectorUsed to set the x,y, and z components of this point
Exceptions
ReferenceFrameExceptionIf *referenceFrame=nullptr
Parameters
referenceFramePointer to a ReferenceFrame this point is expressed in

Definition at line 133 of file FrameVector.hpp.

void RobotDynamics::Math::FrameVector::setToZero ( )
inline

Set x, y, and z components to 0.

Definition at line 103 of file FrameVector.hpp.

Vector3d RobotDynamics::Math::FrameVector::vec ( ) const
inline

Definition at line 192 of file FrameVector.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