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>
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. . More... | |
Vector3d | cross (const Vector3d &vector) const |
Cross product, i.e. . More... | |
double | dot (const FrameVector &frameVector) const |
Dot product between two FrameVectors, i.e. . 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, . More... | |
Math::TransformableGeometricObject * | getTransformableGeometricObject () |
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, . More... | |
void | operator+= (const Vector3d &v) |
void | operator+= (const FrameVector &v) |
Plus euals operator that performs runtime frame checks, . More... | |
void | operator-= (const Vector3d &v) |
void | operator-= (const FrameVector &v) |
Minus euals operator that performs runtime frame checks, . 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 > | |
Vector3d & | operator= (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 |
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.
|
inline |
Default constructor. Initializes its ReferenceFrame to nullptr.
Definition at line 39 of file FrameVector.hpp.
|
inlineexplicit |
Constructor.
referenceFrame | A pointer to a ReferenceFrame |
Definition at line 47 of file FrameVector.hpp.
|
inline |
Constructor.
referenceFrame | A pointer to a ReferenceFrame |
x | Value of the x-coordinate |
y | Value of the y-coordinate |
z | Value of the z-coordinate |
Definition at line 58 of file FrameVector.hpp.
|
inline |
Constructor.
referenceFrame | Pointer to a ReferenceFrame |
vector | A Vector3d used to set the x,y, and z coordinates |
Definition at line 67 of file FrameVector.hpp.
|
inlinevirtual |
Destructor.
Definition at line 74 of file FrameVector.hpp.
|
inline |
copy into new frame vector and change the frame of that
referenceFrame |
Definition at line 93 of file FrameVector.hpp.
|
inline |
Cross product between two FrameVectors, i.e. .
vector |
ReferenceFrameException | If the FrameVectors aren't expressed in the same ReferenceFrame |
Definition at line 163 of file FrameVector.hpp.
Cross product, i.e. .
vector |
Definition at line 175 of file FrameVector.hpp.
|
inline |
Dot product between two FrameVectors, i.e. .
frameVector |
ReferenceFrameException | If the FrameVectors aren't expressed in the same ReferenceFrame |
Definition at line 150 of file FrameVector.hpp.
|
inline |
Computer the angle between two FrameVectors, .
frameVector |
Definition at line 185 of file FrameVector.hpp.
|
inlinevirtual |
Return pointer to this object as type TransformableGeometricObject. See FrameObject::changeFrame for an example of where this method is used.
Implements RobotDynamics::FrameObject.
Definition at line 83 of file FrameVector.hpp.
|
inline |
Times euals operator that performs runtime frame checks, .
typename | of the scale parameter |
scale |
Definition at line 241 of file FrameVector.hpp.
|
inline |
Definition at line 197 of file FrameVector.hpp.
|
inline |
Plus euals operator that performs runtime frame checks, .
v |
Definition at line 215 of file FrameVector.hpp.
|
inline |
Definition at line 204 of file FrameVector.hpp.
|
inline |
Minus euals operator that performs runtime frame checks, .
v |
Definition at line 227 of file FrameVector.hpp.
|
inline |
Set the x, y, and z components and the ReferenceFrame these components are expressed in.
x | The x-component |
y | y-component |
z | z-component |
ReferenceFrameException | If *referenceFrame=nullptr |
referenceFrame | Pointer to a ReferenceFrame this point is expressed in |
Definition at line 116 of file FrameVector.hpp.
|
inline |
Set the x, y, and z components and the ReferenceFrame these components are expressed in.
vector | Used to set the x,y, and z components of this point |
ReferenceFrameException | If *referenceFrame=nullptr |
referenceFrame | Pointer to a ReferenceFrame this point is expressed in |
Definition at line 133 of file FrameVector.hpp.
|
inline |
Set x, y, and z components to 0.
Definition at line 103 of file FrameVector.hpp.
|
inline |
Definition at line 192 of file FrameVector.hpp.