8 #ifndef __RDL_SPATIAL_ACCELERATION_HPP__ 9 #define __RDL_SPATIAL_ACCELERATION_HPP__ 60 const double vx,
const double vy,
const double vz)
61 :
SpatialMotion(bodyFrame, baseFrame, expressedInFrame, wx, wy, wz, vx, vy, vz)
74 :
SpatialMotion(bodyFrame, baseFrame, expressedInFrame, w.x(), w.y(), w.z(), v.x(), v.y(), v.z())
152 #endif //__RDL_SPATIAL_ACCELERATION_HPP__
ReferenceFramePtr getReferenceFrame() const
Get a pointer to the reference frame this FrameObject is expressed in.
SpatialAcceleration(const SpatialAcceleration &spatialAcceleration)
Constructor.
std::vector< SpatialAcceleration, Eigen::aligned_allocator< SpatialAcceleration > > SpatialAccelerationV
EIGEN_STRONG_INLINE double & vz()
Get a reference to the linear-z component.
SpatialAcceleration(ReferenceFramePtr bodyFrame, ReferenceFramePtr baseFrame, ReferenceFramePtr expressedInFrame, const double wx, const double wy, const double wz, const double vx, const double vy, const double vz)
Constructor.
FramePoint operator+(FramePoint p, const FrameVector &v)
EIGEN_STRONG_INLINE double & wx()
Get a reference to the angular-x component.
EIGEN_STRONG_INLINE double & wy()
Get a reference to the angular-y component.
ReferenceFramePtr bodyFrame
SpatialAcceleration(ReferenceFramePtr bodyFrame, ReferenceFramePtr baseFrame, ReferenceFramePtr expressedInFrame, const Vector3d &w, const Vector3d v)
Constructor.
EIGEN_STRONG_INLINE double & vx()
Get a reference to the linear-x component.
SpatialAcceleration(ReferenceFramePtr bodyFrame, ReferenceFramePtr baseFrame, ReferenceFramePtr expressedInFrame, const SpatialVector &v)
Constructor.
std::shared_ptr< ReferenceFrame > ReferenceFramePtr
A SpatialMotion vector is a MotionVector with a RobotDynamics::ReferenceFrame it is expressed in...
void operator+=(const SpatialAcceleration &vector)
Add a SpatialAcceleration, . Frame checks are performed to ensure frame rules are adhered to...
ReferenceFramePtr getBaseFrame() const
Get a SpatialMotions SpatialMotion::baseFrame.
EIGEN_STRONG_INLINE double & wz()
Get a reference to the angular-z component.
void operator-=(const SpatialAcceleration &vector)
Subtract a SpatialAcceleration, . Frame checks are performed to ensure frame rules are adhered to...
EIGEN_STRONG_INLINE double & vy()
Get a reference to the linear-y component.
ReferenceFramePtr getBodyFrame() const
Get a SpatialMotions SpatialMotion::bodyFrame.
ReferenceFramePtr baseFrame
FramePoint operator-(FramePoint p, const FrameVector &v)
SpatialAcceleration. For clarity, the ReferenceFrames are stated as follows. A spatial acceleration i...
void changeFrameWithRelativeMotion(ReferenceFramePtr newFrame, SpatialMotion twistOfCurrentFrameWithRespectToNewFrame, const SpatialMotion &twistOfBodyWrtBaseExpressedInCurrent)
Use this method to change the ReferenceFrame::expressedInFrame of a SpatialAcceleration if there is r...
Namespace for all structures of the RobotDynamics library.
SpatialAcceleration()
Constructor. ReferenceFrame is initialized to nullptr and vector elements to 0.