|
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...
|
|
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...
|
|
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) |
|
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.