#include <MotionVector.hpp>
Public Member Functions | |
MotionVector | cross (const MotionVector &v) |
See V. Duindum thesis p.25 for an explanation of what operator is. It is also in Featherstone p. 25 eq. 2.31 & 2.32. For featherstone notation, it is essentially the operator for spatial vectors. Given two SpatialMotion vectors, and , this method returns . Expanded, it looks like,
The 3d vector operator is equivalent to the operator. See Math::toTildeForm. More... | |
ForceVector | cross (const ForceVector &v) |
See Featherstone p. 25 eq. 2.31 & 2.32. For featherstone notation, it is essentially the operator for spatial vectors. Given a SpatialMotion vector, , and SpatialForceVector, , this method returns . Expanded, it looks like,
The 3d vector operator is equivalent to the operator. See Math::toTildeForm. More... | |
SpatialMatrix | crossf () |
Get the spatial force cross matrix. More... | |
SpatialMatrix | crossm () |
Get the spatial motion cross matrix,
. More... | |
template<typename OtherDerived > | |
MotionVector (const Eigen::MatrixBase< OtherDerived > &other) | |
Constructor. More... | |
EIGEN_STRONG_INLINE | MotionVector () |
Empty constructor. More... | |
MotionVector (const double v0, const double v1, const double v2, const double v3, const double v4, const double v5) | |
Constructor. More... | |
MotionVector | operator%= (const MotionVector &v) |
Operator for performing the RBDA operator for two motion vectors, i.e. . More... | |
ForceVector | operator%= (const ForceVector &v) |
Operator for performing the RBDA operator for a motion vector and a force vector, i.e. . More... | |
MotionVector | operator+= (const MotionVector &v) |
Overloaded += operator for a MotionVector. More... | |
MotionVector & | operator= (const MotionVector &other) |
Overload equal operator. More... | |
EIGEN_STRONG_INLINE void | set (const MotionVector &v) |
Setter. More... | |
EIGEN_STRONG_INLINE SpatialVector | toSpatialVector () const |
Get a copy of a MotionVector as a SpatialVector. More... | |
void | transform (const SpatialTransform &X) |
Transforms a motion vector. Performs . More... | |
MotionVector | transform_copy (const SpatialTransform &X) const |
Copies, transforms, and returns a MotionVector. Performs . More... | |
EIGEN_STRONG_INLINE double & | vx () |
Get a reference to the linear-x component. More... | |
EIGEN_STRONG_INLINE double | vx () const |
Get a copy of the linear-x component. More... | |
EIGEN_STRONG_INLINE double & | vy () |
Get a reference to the linear-y component. More... | |
EIGEN_STRONG_INLINE double | vy () const |
Get a copy of the linear-y component. More... | |
EIGEN_STRONG_INLINE double & | vz () |
Get a reference to the linear-z component. More... | |
EIGEN_STRONG_INLINE double | vz () const |
Get a copy of the linear-z component. More... | |
EIGEN_STRONG_INLINE double & | wx () |
Get a reference to the angular-x component. More... | |
EIGEN_STRONG_INLINE double | wx () const |
Get a copy of the angular-x component. More... | |
EIGEN_STRONG_INLINE double & | wy () |
Get a reference to the angular-y component. More... | |
EIGEN_STRONG_INLINE double | wy () const |
Get a copy of the angular-y component. More... | |
EIGEN_STRONG_INLINE double & | wz () |
Get a reference to the angular-z component. More... | |
EIGEN_STRONG_INLINE double | wz () const |
Get a copy of the angular-z component. More... | |
Public Member Functions inherited from RobotDynamics::Math::SpatialVector | |
EIGEN_STRONG_INLINE Vector3d | getAngularPart () const |
EIGEN_STRONG_INLINE Vector3d | getLinearPart () const |
template<typename OtherDerived > | |
SpatialVector & | operator= (const Eigen::MatrixBase< OtherDerived > &other) |
EIGEN_STRONG_INLINE void | set (const double &v0, const double &v1, const double &v2, const double &v3, const double &v4, const double &v5) |
EIGEN_STRONG_INLINE void | set (const Vector3d &angularPart, const Vector3d &linearPart) |
void | setAngularPart (const Vector3d &v) |
void | setLinearPart (const Vector3d &v) |
template<typename OtherDerived > | |
SpatialVector (const Eigen::MatrixBase< OtherDerived > &other) | |
EIGEN_STRONG_INLINE | SpatialVector () |
EIGEN_STRONG_INLINE | SpatialVector (const double &v0, const double &v1, const double &v2, const double &v3, const double &v4, const double &v5) |
Additional Inherited Members | |
Public Types inherited from RobotDynamics::Math::SpatialVector | |
typedef Eigen::Matrix< double, 6, 1 > | Base |
Definition at line 24 of file MotionVector.hpp.
|
inline |
|
inline |
Empty constructor.
Definition at line 51 of file MotionVector.hpp.
|
inline |
Constructor.
v0 | x-angular |
v1 | y-angular |
v2 | z-angular |
v3 | x-linear |
v4 | y-linear |
v5 | z-linear |
Definition at line 64 of file MotionVector.hpp.
MotionVector RobotDynamics::Math::MotionVector::cross | ( | const MotionVector & | v | ) |
See V. Duindum thesis p.25 for an explanation of what operator is. It is also in Featherstone p. 25 eq. 2.31 & 2.32. For featherstone notation, it is essentially the operator for spatial vectors. Given two SpatialMotion vectors, and , this method returns . Expanded, it looks like,
The 3d vector operator is equivalent to the operator. See Math::toTildeForm.
Definition at line 14 of file MotionVector.cpp.
ForceVector RobotDynamics::Math::MotionVector::cross | ( | const ForceVector & | v | ) |
See Featherstone p. 25 eq. 2.31 & 2.32. For featherstone notation, it is essentially the operator for spatial vectors. Given a SpatialMotion vector, , and SpatialForceVector, , this method returns . Expanded, it looks like,
The 3d vector operator is equivalent to the operator. See Math::toTildeForm.
Definition at line 36 of file MotionVector.cpp.
|
inline |
|
inline |
|
inline |
Operator for performing the RBDA operator for two motion vectors, i.e. .
v |
Definition at line 290 of file MotionVector.hpp.
|
inline |
Operator for performing the RBDA operator for a motion vector and a force vector, i.e. .
v |
Definition at line 301 of file MotionVector.hpp.
|
inline |
Overloaded += operator for a MotionVector.
Definition at line 310 of file MotionVector.hpp.
|
inline |
Overload equal operator.
other |
Definition at line 42 of file MotionVector.hpp.
|
inline |
Setter.
v | Sets the values equal to those stored in v |
Definition at line 84 of file MotionVector.hpp.
|
inline |
Get a copy of a MotionVector as a SpatialVector.
Definition at line 75 of file MotionVector.hpp.
|
inlinevirtual |
Transforms a motion vector. Performs .
X |
Implements RobotDynamics::Math::TransformableGeometricObject.
Definition at line 201 of file MotionVector.hpp.
|
inline |
Copies, transforms, and returns a MotionVector. Performs .
X |
Definition at line 217 of file MotionVector.hpp.
|
inline |
Get a reference to the linear-x component.
Definition at line 147 of file MotionVector.hpp.
|
inline |
Get a copy of the linear-x component.
Definition at line 174 of file MotionVector.hpp.
|
inline |
Get a reference to the linear-y component.
Definition at line 156 of file MotionVector.hpp.
|
inline |
Get a copy of the linear-y component.
Definition at line 183 of file MotionVector.hpp.
|
inline |
Get a reference to the linear-z component.
Definition at line 165 of file MotionVector.hpp.
|
inline |
Get a copy of the linear-z component.
Definition at line 192 of file MotionVector.hpp.
|
inline |
Get a reference to the angular-x component.
Definition at line 93 of file MotionVector.hpp.
|
inline |
Get a copy of the angular-x component.
Definition at line 120 of file MotionVector.hpp.
|
inline |
Get a reference to the angular-y component.
Definition at line 102 of file MotionVector.hpp.
|
inline |
Get a copy of the angular-y component.
Definition at line 129 of file MotionVector.hpp.
|
inline |
Get a reference to the angular-z component.
Definition at line 111 of file MotionVector.hpp.
|
inline |
Get a copy of the angular-z component.
Definition at line 138 of file MotionVector.hpp.