Robot Dynamics Library
Classes | Typedefs | Functions | Variables
Reference Frame

Classes

class  RobotDynamics::ReferenceFrame
 ReferenceFrame object used to tell what frame objects are expressed in. Every ReferenceFrame has a pointer to its parent ReferenceFrame. This parent frame is NOT allowed to be nullptr. The ONLY ReferenceFrame that is allowed to have parentFrame=nullptr is the world frame. There is only one world frame and it can be accessed by the static method ReferenceFrame::getWorldFrame() which will return a shared_ptr to the world frame. This class and its implementation are an adaptation of ReferenceFrame.java by Jerry Pratt and the IHMC Robotics Group. More...
 
class  RobotDynamics::FixedReferenceFrame
 
class  RobotDynamics::ReferenceFrameException
 A custom exception for frame operations. More...
 
class  RobotDynamics::FrameObject
 An interface that objects with a ReferenceFrame extend to inherit the FrameObject::changeFrame method. More...
 
class  RobotDynamics::Math::FrameOrientation
 A Frame object that represents an orientation(quaternion) relative to a reference frame. More...
 
class  RobotDynamics::Math::FramePoint
 A FramePoint is a 3D point that is expressed in a ReferenceFrame. To change the ReferenceFrame a FramePoint is expressed in, you may call the inhereted FrameObject::changeFrame method and supply it a pointer to the ReferenceFrame you wish to have the FramePoint expressed in. This class and its implementation are an adaptation of FramePoint.java by Jerry Pratt and the IHMC Robotics Group. More...
 
class  RobotDynamics::Math::FrameVector
 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...
 
class  RobotDynamics::Math::FrameVectorPair
 A FrameVector is a pair of 3D vector with a ReferenceFrame. More...
 
class  RobotDynamics::Math::SpatialAcceleration
 SpatialAcceleration. For clarity, the ReferenceFrames are stated as follows. A spatial acceleration is the acceleration of the SpatialAcceleration::bodyFrame with respect to the SpatialAcceleration::baseFrame expressed in the SpatialAcceleration::expressedInFrame. More...
 
class  RobotDynamics::Math::SpatialForce
 A SpatialForce is a spatial vector with the angular part being three moments and the linear part being 3 linear forces. More...
 
class  RobotDynamics::Math::SpatialMomentum
 A SpatialMomentum is a Momentum expressed in a RobotDynamics::ReferenceFrame. The angular portion of the vector is referred to as $k$ and the linear portion as $l$. More...
 
class  RobotDynamics::Math::SpatialMotion
 A SpatialMotion vector is a MotionVector with a RobotDynamics::ReferenceFrame it is expressed in. This allows for runtime checks that frame rules are obeyed and makes it easy to change the frame the metion vector is expressed in. As with a SpatialAcceleration, a SpatialMotion vector is the spatial velocity of a SpatialMotion::bodyFrame relative to a SpatialMotion::baseFrame and is expressed in RobotDynamics::FrameObject::referenceFrame. More...
 
class  RobotDynamics::Math::SpatialInertia
 A Math::SpatialInertia is a RigidBodyInertia explicitly expressed in a RobotDynamics::ReferenceFrame. The frame a Math::SpatialInertia is expressed in can be changed by calling RobotDynamics::FrameObject::changeFrame. More...
 

Typedefs

typedef std::shared_ptr< ReferenceFrameRobotDynamics::ReferenceFramePtr
 
typedef std::shared_ptr< FixedReferenceFrameRobotDynamics::FixedReferenceFramePtr
 
typedef std::vector< ReferenceFramePtrRobotDynamics::ReferenceFramePtrV
 
typedef std::vector< FixedReferenceFramePtrRobotDynamics::FixedReferenceFramePtrV
 

Functions

RobotDynamics::Math::FramePoint RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame (Model &model, const Math::VectorNd &q, bool update_kinematics=true)
 Computes the center of buoyancy and updates the center of buoyancy reference frame of the model. More...
 
RobotDynamics::Math::FramePoint RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame (Model &model, const Math::VectorNd &q, const Math::Quaternion &orientation, bool update_kinematics=true)
 Computes the center of buoyancy and updates the center of buoyancy reference frame of the model. More...
 
RobotDynamics::Math::FramePoint RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame (Model &model, const Math::VectorNd &q, const Math::Vector3d &euler_ypr, bool update_kinematics=true)
 Computes the center of buoyancy and updates the center of buoyancy reference frame of the model. More...
 
void RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame (Model &model, const Math::Vector3d &p_cob)
 Updates the center of buoyancy frame of the robot be at location p_com and aligned with world frame. More...
 
void RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame (Model &model, const Math::Vector3d &p_cob, const Math::Quaternion &orientation)
 Updates the center of buoyancy frame of the robot be at location p_com and aligned with world frame. More...
 
void RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame (Model &model, const Math::Vector3d &p_cob, const Math::Vector3d &euler_ypr)
 Updates the center of buoyancy frame of the robot be at location p_com and to have orientation defined by the yaw/pitch/roll angles in euler_ypr argument. The euler_ypr argument is optional and if not provided the center of buoyancy reference frame will be aligned with world. More...
 
void RobotDynamics::Utils::calcCenterOfMass (Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, Math::FramePoint &com, Math::FrameVector &com_velocity, Math::FrameVector *angular_momentum=nullptr, bool update_kinematics=true)
 Computes the Center of Mass (COM) and optionally its linear velocity and/or angular momentum. More...
 
void RobotDynamics::Utils::calcCenterOfMass (Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, Math::FramePoint &com, Math::FrameVector *com_velocity=nullptr, bool update_kinematics=true)
 Computes the Center of Mass (COM) and optionally its linear velocity. More...
 
RobotDynamics::Math::FramePoint RobotDynamics::Utils::updateCenterOfMassFrame (Model &model, const Math::VectorNd &q, bool update_kinematics=true)
 Computes the center of mass and updates the center of mass reference frame of the model. More...
 
RobotDynamics::Math::FramePoint RobotDynamics::Utils::updateCenterOfMassFrame (Model &model, const Math::VectorNd &q, const Math::Vector3d &euler_ypr, bool update_kinematics=true)
 Computes the center of mass and updates the center of mass reference frame of the model. More...
 
RobotDynamics::Math::FramePoint RobotDynamics::Utils::updateCenterOfMassFrame (Model &model, const Math::VectorNd &q, const Math::Quaternion &orientation, bool update_kinematics=true)
 Computes the center of mass and updates the center of mass reference frame of the model. More...
 
void RobotDynamics::Utils::updateCenterOfMassFrame (Model &model, const Math::Vector3d &p_com)
 Updates the center of mass frame of the robot be at location p_com, aligned with world frame. More...
 
void RobotDynamics::Utils::updateCenterOfMassFrame (Model &model, const Math::Vector3d &p_com, const Math::Vector3d &euler_ypr)
 Updates the center of mass frame of the robot be at location p_com and to have orientation defined by the yaw/pitch/roll angles in euler_ypr argument. The euler_ypr argument is optional and if not provided the center of mass reference frame will be aligned with world. More...
 
void RobotDynamics::Utils::updateCenterOfMassFrame (Model &model, const Math::Vector3d &p_com, const Math::Quaternion &orientation)
 Updates the center of mass frame of the robot be at location p_com and to have orientation defined by the orientation argument. The quaternion argument is optional and if not provided the center of mass reference frame will be aligned with world. More...
 
 RobotDynamics::ReferenceFrame::ReferenceFrame (const ReferenceFrame &referenceFrameToCopy)
 Copy constructor. More...
 
 RobotDynamics::ReferenceFrame::ReferenceFrame (const std::string &frameName, ReferenceFramePtr parentFrame, const RobotDynamics::Math::SpatialTransform &transformFromParent, bool isBodyFrame, unsigned int movableBodyId)
 Constructor. More...
 
 RobotDynamics::ReferenceFrame::ReferenceFrame ()
 Empty constructor. All contained ptrs will be initialize to nullptr. More...
 
ReferenceFrameRobotDynamics::ReferenceFrame::getRootFrame ()
 
virtual RobotDynamics::ReferenceFrame::~ReferenceFrame ()
 Destructor. More...
 
void RobotDynamics::ReferenceFrame::update ()
 Recalculates this frames ReferenceFrame::transformToRoot and ReferenceFrame::inverseTransformToRoot which are used by FrameObject::changeFrame to change the ReferenceFrame FrameObjects are expressed in. If you create a ReferenceFrame you MUST call update every tic each time the frames ReferenceFrame::transformFromParent changes. Each time ReferenceFrame::setTransformFromParent changes, you need to call ReferenceFrame::transformFromParent before you call ReferenceFrame::update(). More...
 
void RobotDynamics::ReferenceFrame::getTransformToDesiredFrame (RobotDynamics::Math::SpatialTransform &transformToPack, ReferenceFramePtr desiredFrame)
 Get the spatial transform from this frame to desiredFrame and store it in transformToPack. More...
 
virtual RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::getTransformToDesiredFrame (ReferenceFramePtr desiredFrame)
 Get the spatial transform from this frame to desiredFrame and store it in transformToPack. More...
 
void RobotDynamics::ReferenceFrame::verifyFramesHaveSameRoot (ReferenceFramePtr frame)
 Check if two frames have the same roots. More...
 
void RobotDynamics::ReferenceFrame::setTransformFromParent (const RobotDynamics::Math::SpatialTransform &transformFromParent)
 Set a frames ReferenceFrame::transformToParent. For frames connected by a joint, this needs to be updated every tic BEFORE calling the ReferenceFrame::update method. More...
 
void RobotDynamics::ReferenceFrame::checkReferenceFramesMatch (ReferenceFramePtr referenceFrame) const
 Check if the argument ReferenceFrame equals this. More...
 
void RobotDynamics::ReferenceFrame::checkReferenceFramesMatch (ReferenceFrame *referenceFrame) const
 
virtual RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::getTransformToRoot ()
 Get this frames ReferenceFrame::transformToRoot. More...
 
virtual RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::getInverseTransformToRoot ()
 Get this frames ReferenceFrame::inverseTransformToRoot. More...
 
ReferenceFramePtr RobotDynamics::ReferenceFrame::getParentFrame ()
 get a pointer to this frames parent More...
 
std::string RobotDynamics::ReferenceFrame::getName () const
 Get the frame name. More...
 
static ReferenceFramePtr RobotDynamics::ReferenceFrame::createARootFrame (const std::string &frameName)
 Creates a root frame with ReferenceFrame::parentFrame=nullptr. More...
 
static ReferenceFramePtr RobotDynamics::ReferenceFrame::getWorldFrame ()
 Get a pointer to the world frame. More...
 
RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::getTransformFromParent ()
 Get spatial transform from parent to this frame. More...
 
RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::getTransformToParent ()
 Get spatial transform this frame to its parent. More...
 
bool RobotDynamics::ReferenceFrame::getIsWorldFrame () const
 Get a boolean telling if this frame is the world frame. More...
 
unsigned int RobotDynamics::ReferenceFrame::getMovableBodyId () const
 Get the ID of the movable body this frame is attached to. More...
 
bool RobotDynamics::ReferenceFrame::getIsBodyFrame () const
 Get boolean telling if this frame is a body frame or not. If it is a body frame, A pointer to this frame would be stored in Model::bodyFrames vector. More...
 
ReferenceFrameRobotDynamics::ReferenceFrame::operator= (const ReferenceFrame &other)
 
 RobotDynamics::ReferenceFrame::ReferenceFrame (const std::string &frameName, bool isWorldFrame, unsigned int movableBodyId, bool isBodyFrame)
 
static ReferenceFramePtr RobotDynamics::ReferenceFrame::createAWorldFrame (const std::string &frameName="world")
 Helper method to create a world frame. More...
 
 RobotDynamics::FixedReferenceFrame::FixedReferenceFrame (const FixedReferenceFrame &)=delete
 
void RobotDynamics::FixedReferenceFrame::operator= (const FixedReferenceFrame &)=delete
 
 RobotDynamics::FixedReferenceFrame::FixedReferenceFrame (const std::string &frameName, ReferenceFramePtr parentFrame, const RobotDynamics::Math::SpatialTransform &transformFromParent, unsigned int movableBodyId)
 
virtual RobotDynamics::FixedReferenceFrame::~FixedReferenceFrame ()
 
RobotDynamics::Math::SpatialTransform RobotDynamics::FixedReferenceFrame::getTransformToRoot () override
 Get this frames ReferenceFrame::transformToRoot. More...
 
RobotDynamics::Math::SpatialTransform RobotDynamics::FixedReferenceFrame::getInverseTransformToRoot () override
 Get this frames ReferenceFrame::inverseTransformToRoot. More...
 

Variables

static ReferenceFramePtr RobotDynamics::ReferenceFrame::worldFrame = ReferenceFrame::createAWorldFrame()
 
std::string RobotDynamics::ReferenceFrame::frameName
 
ReferenceFramePtr RobotDynamics::ReferenceFrame::parentFrame
 
RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::transformFromParent
 
RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::transformToRoot
 
RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::inverseTransformToRoot
 
ReferenceFrameRobotDynamics::ReferenceFrame::rootFrame
 
bool RobotDynamics::ReferenceFrame::isWorldFrame
 
bool RobotDynamics::ReferenceFrame::isBodyFrame
 
unsigned int RobotDynamics::ReferenceFrame::movableBodyId
 

Detailed Description

The ReferenceFrame object is the foundation of the way kinematics are handled. Each time a body is added via RobotDynamics::Model::addBody(), a pointer to a ReferenceFrame is created for that body and added to either RobotDynamics::Model::bodyFrames or RobotDynamics::Model::fixedBodyFrames depending on the type of body that is added. Additionally a reference frame is placed on the center of mass of each body and is stored in RobotDynamics::Model::bodyCenteredFrames.

These reference frames can then be used to explicitly express geometric entities(SpatialMotion, SpatialMomentum, SpatialForce, etc) in a reference frame. To query the name of a reference frame a geometric object is expressed in, you may call the ReferenceFrame::getName() method on the objects ReferenceFrame. Furthermore, to transform a framed geometric entity(anything that inheritcs from the RobotDynamics::FrameObject) into a different reference frame, you may simply call the RobotDynamics::FrameObject::changeFrame method and supply it a pointer to the frame you want the geometric object to be transformed to.

Note
If you create your own ReferenceFrame outside of those stored in the RobotDynamics::Model, you are required to call RobotDynamics::ReferenceFrame::update every time the created frames' ReferenceFrame::transformFromParent changes. The only exception to this is for RobotDynamics::FixedReferenceFrame objects. By definition, these frames are fixed and thus their ReferenceFrame::transformFromParent is set on construction and never changes, so after construction you do not need to call RobotDynamics::ReferenceFrame::update.

Typedef Documentation

◆ FixedReferenceFramePtr

◆ FixedReferenceFramePtrV

◆ ReferenceFramePtr

◆ ReferenceFramePtrV

Function Documentation

◆ calcCenterOfMass() [1/2]

void RobotDynamics::Utils::calcCenterOfMass ( Model model,
const Math::VectorNd q,
const Math::VectorNd qdot,
Math::FramePoint com,
Math::FrameVector com_velocity,
Math::FrameVector angular_momentum = nullptr,
bool  update_kinematics = true 
)

Computes the Center of Mass (COM) and optionally its linear velocity and/or angular momentum.

When only interested in computing the location of the COM you can use nullptr as value for com_velocity/angular_momentum.

Parameters
modelThe model for which we want to compute the COM
qThe current joint positions
qdotThe current joint velocities
comlocation of the Center of Mass of the model in world frame
com_velocitylinear velocity of the COM in world frame
angular_momentum(optional output) angular momentum of the model at the COM in a reference frame aligned with the world frame, but located at the center of mass
update_kinematics(optional input) whether the kinematics should be updated (defaults to true)

◆ calcCenterOfMass() [2/2]

void RobotDynamics::Utils::calcCenterOfMass ( Model model,
const Math::VectorNd q,
const Math::VectorNd qdot,
Math::FramePoint com,
Math::FrameVector com_velocity = nullptr,
bool  update_kinematics = true 
)

Computes the Center of Mass (COM) and optionally its linear velocity.

When only interested in computing the location of the COM you can use nullptr as value for com_velocity.

Parameters
modelThe model for which we want to compute the COM
qThe current joint positions
qdotThe current joint velocities
com(output) location of the Center of Mass of the model in world frame
com_velocity(optional output) linear velocity of the COM in world frame
update_kinematics(optional input) whether the kinematics should be updated (defaults to true)

◆ checkReferenceFramesMatch() [1/2]

void RobotDynamics::ReferenceFrame::checkReferenceFramesMatch ( ReferenceFrame referenceFrame) const

◆ checkReferenceFramesMatch() [2/2]

void RobotDynamics::ReferenceFrame::checkReferenceFramesMatch ( ReferenceFramePtr  referenceFrame) const

Check if the argument ReferenceFrame equals this.

Parameters
referenceFrame

◆ createARootFrame()

static ReferenceFramePtr RobotDynamics::ReferenceFrame::createARootFrame ( const std::string &  frameName)
inlinestatic

Creates a root frame with ReferenceFrame::parentFrame=nullptr.

Parameters
frameName
Returns
pointer to the created root frame

◆ createAWorldFrame()

static ReferenceFramePtr RobotDynamics::ReferenceFrame::createAWorldFrame ( const std::string &  frameName = "world")
inlinestaticprotected

Helper method to create a world frame.

Parameters
frameName
Returns
Pointer to the created world frame

◆ FixedReferenceFrame() [1/2]

RobotDynamics::FixedReferenceFrame::FixedReferenceFrame ( const FixedReferenceFrame )
privatedelete

◆ FixedReferenceFrame() [2/2]

RobotDynamics::FixedReferenceFrame::FixedReferenceFrame ( const std::string &  frameName,
ReferenceFramePtr  parentFrame,
const RobotDynamics::Math::SpatialTransform transformFromParent,
unsigned int  movableBodyId 
)
inline

◆ getInverseTransformToRoot() [1/2]

virtual RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::getInverseTransformToRoot ( )
inlinevirtual

◆ getInverseTransformToRoot() [2/2]

RobotDynamics::Math::SpatialTransform RobotDynamics::FixedReferenceFrame::getInverseTransformToRoot ( )
inlineoverridevirtual

◆ getIsBodyFrame()

bool RobotDynamics::ReferenceFrame::getIsBodyFrame ( ) const
inline

Get boolean telling if this frame is a body frame or not. If it is a body frame, A pointer to this frame would be stored in Model::bodyFrames vector.

Returns
Boolean true if this frame is a body frame, false otherwise

◆ getIsWorldFrame()

bool RobotDynamics::ReferenceFrame::getIsWorldFrame ( ) const
inline

Get a boolean telling if this frame is the world frame.

Returns
Boolean true if this frame is world frame, false otherwise

◆ getMovableBodyId()

unsigned int RobotDynamics::ReferenceFrame::getMovableBodyId ( ) const
inline

Get the ID of the movable body this frame is attached to.

Returns
Unsigned int corresponding to the movable body this frame is attached to

◆ getName()

std::string RobotDynamics::ReferenceFrame::getName ( ) const
inline

Get the frame name.

Returns
ReferenceFrame::framenName

◆ getParentFrame()

ReferenceFramePtr RobotDynamics::ReferenceFrame::getParentFrame ( )
inline

get a pointer to this frames parent

Returns
ReferenceFrame::parentFrame

◆ getRootFrame()

ReferenceFrame* RobotDynamics::ReferenceFrame::getRootFrame ( )
inline

◆ getTransformFromParent()

RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::getTransformFromParent ( )
inline

Get spatial transform from parent to this frame.

Returns
SpatialTransform from parent to this frame

◆ getTransformToDesiredFrame() [1/2]

RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::getTransformToDesiredFrame ( ReferenceFramePtr  desiredFrame)
virtual

Get the spatial transform from this frame to desiredFrame and store it in transformToPack.

Parameters
desiredFrameThe resulting transform will transform vectors into desiredFrame
Returns
Spatial transform that will transform vectors into the ReferenceFrame desiredFrame

◆ getTransformToDesiredFrame() [2/2]

void RobotDynamics::ReferenceFrame::getTransformToDesiredFrame ( RobotDynamics::Math::SpatialTransform transformToPack,
ReferenceFramePtr  desiredFrame 
)
inline

Get the spatial transform from this frame to desiredFrame and store it in transformToPack.

Parameters
transformToPackResulting transform to the desired frame will be stored here
desiredFrameThe resulting transform will transform vectors into desiredFrame

◆ getTransformToParent()

RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::getTransformToParent ( )
inline

Get spatial transform this frame to its parent.

Returns
SpatialTransform from this frame to parent

◆ getTransformToRoot() [1/2]

virtual RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::getTransformToRoot ( )
inlinevirtual

◆ getTransformToRoot() [2/2]

RobotDynamics::Math::SpatialTransform RobotDynamics::FixedReferenceFrame::getTransformToRoot ( )
inlineoverridevirtual

◆ getWorldFrame()

static ReferenceFramePtr RobotDynamics::ReferenceFrame::getWorldFrame ( )
inlinestatic

Get a pointer to the world frame.

Returns
Pointer to world frame

◆ operator=() [1/2]

void RobotDynamics::FixedReferenceFrame::operator= ( const FixedReferenceFrame )
privatedelete

◆ operator=() [2/2]

ReferenceFrame& RobotDynamics::ReferenceFrame::operator= ( const ReferenceFrame other)
inline

◆ ReferenceFrame() [1/4]

RobotDynamics::ReferenceFrame::ReferenceFrame ( )
inline

Empty constructor. All contained ptrs will be initialize to nullptr.

◆ ReferenceFrame() [2/4]

RobotDynamics::ReferenceFrame::ReferenceFrame ( const ReferenceFrame referenceFrameToCopy)
inline

Copy constructor.

Parameters
referenceFrameToCopy

◆ ReferenceFrame() [3/4]

RobotDynamics::ReferenceFrame::ReferenceFrame ( const std::string &  frameName,
bool  isWorldFrame,
unsigned int  movableBodyId,
bool  isBodyFrame 
)
inlineprotected

Constructor that creates a top level frame with parent=nullptr, and transforms to root being identity transform.

Parameters
frameName
isWorldFrameTrue of creating the world frame, false if it's just a root frame
movableBodyId
isBodyFrame

◆ ReferenceFrame() [4/4]

RobotDynamics::ReferenceFrame::ReferenceFrame ( const std::string &  frameName,
ReferenceFramePtr  parentFrame,
const RobotDynamics::Math::SpatialTransform transformFromParent,
bool  isBodyFrame,
unsigned int  movableBodyId 
)
inline

Constructor.

Parameters
frameNameName of frame
parentFramePointer to this frames parent ReferenceFrame
transformFromParentSpatial transform from the parent frames perspective to this frame
isBodyFrameBoolean true if this frame is a body frame(i.e. will be stored in Model::bodyFrames), false otherwise
movableBodyIdThe ID of the movable body this frame is attached to. For frames attached to fixed bodies, this should be FixedBody::mMovableParent

◆ setTransformFromParent()

void RobotDynamics::ReferenceFrame::setTransformFromParent ( const RobotDynamics::Math::SpatialTransform transformFromParent)
inline

Set a frames ReferenceFrame::transformToParent. For frames connected by a joint, this needs to be updated every tic BEFORE calling the ReferenceFrame::update method.

Parameters
transformFromParentThe new ReferenceFrame::transformFromParent

◆ update()

void RobotDynamics::ReferenceFrame::update ( )

Recalculates this frames ReferenceFrame::transformToRoot and ReferenceFrame::inverseTransformToRoot which are used by FrameObject::changeFrame to change the ReferenceFrame FrameObjects are expressed in. If you create a ReferenceFrame you MUST call update every tic each time the frames ReferenceFrame::transformFromParent changes. Each time ReferenceFrame::setTransformFromParent changes, you need to call ReferenceFrame::transformFromParent before you call ReferenceFrame::update().

◆ updateCenterOfBuoyancyFrame() [1/6]

void RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame ( Model model,
const Math::Vector3d p_cob 
)

Updates the center of buoyancy frame of the robot be at location p_com and aligned with world frame.

Parameters
modelThe model for which we want to compute the COB
p_comThe cob position in world frame

◆ updateCenterOfBuoyancyFrame() [2/6]

void RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame ( Model model,
const Math::Vector3d p_cob,
const Math::Quaternion orientation 
)

Updates the center of buoyancy frame of the robot be at location p_com and aligned with world frame.

Parameters
modelThe model for which we want to compute the COB
p_comThe cob position in world frame
orientationOrientation of the com frame

◆ updateCenterOfBuoyancyFrame() [3/6]

void RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame ( Model model,
const Math::Vector3d p_cob,
const Math::Vector3d euler_ypr 
)

Updates the center of buoyancy frame of the robot be at location p_com and to have orientation defined by the yaw/pitch/roll angles in euler_ypr argument. The euler_ypr argument is optional and if not provided the center of buoyancy reference frame will be aligned with world.

Parameters
modelThe model for which we want to compute the COB
p_comThe cob position in world frame
euler_yprThe desired orientation of the center of buoyancy frame

◆ updateCenterOfBuoyancyFrame() [4/6]

RobotDynamics::Math::FramePoint RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame ( Model model,
const Math::VectorNd q,
bool  update_kinematics = true 
)

Computes the center of buoyancy and updates the center of buoyancy reference frame of the model.

Parameters
modelThe model for which we want to compute the COB
qThe current joint positions
euler_yprThe desired orientation of the center of buoyancy frame. Defaults to [0, 0, 0] in which case it would be aligned with world frame
update_kinematics(optional input) whether the kinematics should be updated (defaults to true)
Returns
a frame point that represents the position of the origin of the center of buoyancy frame expressed in world frame

◆ updateCenterOfBuoyancyFrame() [5/6]

RobotDynamics::Math::FramePoint RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame ( Model model,
const Math::VectorNd q,
const Math::Quaternion orientation,
bool  update_kinematics = true 
)

Computes the center of buoyancy and updates the center of buoyancy reference frame of the model.

Parameters
modelThe model for which we want to compute the COB
qThe current joint positions
orientationThe desired orientation of the center of buoyancy frame
update_kinematics(optional input) whether the kinematics should be updated (defaults to true)
Returns
a frame point that represents the position of the origin of the center of buoyancy frame expressed in world frame

◆ updateCenterOfBuoyancyFrame() [6/6]

RobotDynamics::Math::FramePoint RobotDynamics::HydroUtils::updateCenterOfBuoyancyFrame ( Model model,
const Math::VectorNd q,
const Math::Vector3d euler_ypr,
bool  update_kinematics = true 
)

Computes the center of buoyancy and updates the center of buoyancy reference frame of the model.

Parameters
modelThe model for which we want to compute the COB
qThe current joint positions
euler_yprThe desired orientation of the center of buoyancy frame
update_kinematics(optional input) whether the kinematics should be updated (defaults to true)
Returns
a frame point that represents the position of the origin of the center of buoyancy frame expressed in world frame

◆ updateCenterOfMassFrame() [1/6]

void RobotDynamics::Utils::updateCenterOfMassFrame ( Model model,
const Math::Vector3d p_com 
)

Updates the center of mass frame of the robot be at location p_com, aligned with world frame.

Parameters
modelThe model for which we want to compute the COM
p_comThe com position in world frame

◆ updateCenterOfMassFrame() [2/6]

void RobotDynamics::Utils::updateCenterOfMassFrame ( Model model,
const Math::Vector3d p_com,
const Math::Quaternion orientation 
)

Updates the center of mass frame of the robot be at location p_com and to have orientation defined by the orientation argument. The quaternion argument is optional and if not provided the center of mass reference frame will be aligned with world.

Parameters
modelThe model for which we want to compute the COM
p_comThe com position in world frame
orientationThe desired orientation of the center of mass frame

◆ updateCenterOfMassFrame() [3/6]

void RobotDynamics::Utils::updateCenterOfMassFrame ( Model model,
const Math::Vector3d p_com,
const Math::Vector3d euler_ypr 
)

Updates the center of mass frame of the robot be at location p_com and to have orientation defined by the yaw/pitch/roll angles in euler_ypr argument. The euler_ypr argument is optional and if not provided the center of mass reference frame will be aligned with world.

Parameters
modelThe model for which we want to compute the COM
p_comThe com position in world frame
euler_yprThe desired orientation of the center of mass frame

◆ updateCenterOfMassFrame() [4/6]

RobotDynamics::Math::FramePoint RobotDynamics::Utils::updateCenterOfMassFrame ( Model model,
const Math::VectorNd q,
bool  update_kinematics = true 
)

Computes the center of mass and updates the center of mass reference frame of the model.

Parameters
modelThe model for which we want to compute the COM
qThe current joint positions
update_kinematics(optional input) whether the kinematics should be updated (defaults to true)
Returns
a frame point that represents the position of the origin of the center of mass frame expressed in world frame

◆ updateCenterOfMassFrame() [5/6]

RobotDynamics::Math::FramePoint RobotDynamics::Utils::updateCenterOfMassFrame ( Model model,
const Math::VectorNd q,
const Math::Quaternion orientation,
bool  update_kinematics = true 
)

Computes the center of mass and updates the center of mass reference frame of the model.

Parameters
modelThe model for which we want to compute the COM
qThe current joint positions
orientationThe desired orientation of the center of mass frame
update_kinematics(optional input) whether the kinematics should be updated (defaults to true)
Returns
a frame point that represents the position of the origin of the center of mass frame expressed in world frame

◆ updateCenterOfMassFrame() [6/6]

RobotDynamics::Math::FramePoint RobotDynamics::Utils::updateCenterOfMassFrame ( Model model,
const Math::VectorNd q,
const Math::Vector3d euler_ypr,
bool  update_kinematics = true 
)

Computes the center of mass and updates the center of mass reference frame of the model.

Parameters
modelThe model for which we want to compute the COM
qThe current joint positions
euler_yprThe desired orientation of the center of mass frame
update_kinematics(optional input) whether the kinematics should be updated (defaults to true)
Returns
a frame point that represents the position of the origin of the center of mass frame expressed in world frame

◆ verifyFramesHaveSameRoot()

void RobotDynamics::ReferenceFrame::verifyFramesHaveSameRoot ( ReferenceFramePtr  frame)

Check if two frames have the same roots.

Exceptions
ReferenceFrameExceptionif the frames do not have the same roots
Parameters
frame

◆ ~FixedReferenceFrame()

virtual RobotDynamics::FixedReferenceFrame::~FixedReferenceFrame ( )
inlinevirtual

◆ ~ReferenceFrame()

virtual RobotDynamics::ReferenceFrame::~ReferenceFrame ( )
inlinevirtual

Destructor.

Variable Documentation

◆ frameName

std::string RobotDynamics::ReferenceFrame::frameName
protected

A frames name

◆ inverseTransformToRoot

RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::inverseTransformToRoot
protected

SpatialTransform to a frame from the root frame

◆ isBodyFrame

bool RobotDynamics::ReferenceFrame::isBodyFrame
protected

True if a frame is a body frame, false otherwise. Body frame pointers are stored in Model::bodyFrames

◆ isWorldFrame

bool RobotDynamics::ReferenceFrame::isWorldFrame
protected

True if a frame is the world frame, false otherwise

◆ movableBodyId

unsigned int RobotDynamics::ReferenceFrame::movableBodyId
protected

The body ID of the movable body a frame is attached to

◆ parentFrame

ReferenceFramePtr RobotDynamics::ReferenceFrame::parentFrame
protected

Pointer to a frames parent frames

◆ rootFrame

ReferenceFrame* RobotDynamics::ReferenceFrame::rootFrame
protected

◆ transformFromParent

RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::transformFromParent
protected

SpatialTransform to a frame from its parent

◆ transformToRoot

RobotDynamics::Math::SpatialTransform RobotDynamics::ReferenceFrame::transformToRoot
protected

SpatialTransform from a frame to the root frame

◆ worldFrame

ReferenceFramePtr RobotDynamics::ReferenceFrame::worldFrame = ReferenceFrame::createAWorldFrame()
staticprotected

Static world frame pointer