Public Member Functions | Static Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
RobotDynamics::ReferenceFrame Class Reference

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

#include <ReferenceFrame.hpp>

Inheritance diagram for RobotDynamics::ReferenceFrame:
Inheritance graph
[legend]

Public Member Functions

void checkReferenceFramesMatch (ReferenceFramePtr referenceFrame) const
 Check if the argument ReferenceFrame equals this. More...
 
void checkReferenceFramesMatch (ReferenceFrame *referenceFrame) const
 
virtual RobotDynamics::Math::SpatialTransform getInverseTransformToRoot ()
 Get this frames ReferenceFrame::inverseTransformToRoot. More...
 
bool 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...
 
bool getIsWorldFrame () const
 Get a boolean telling if this frame is the world frame. More...
 
unsigned int getMovableBodyId () const
 Get the ID of the movable body this frame is attached to. More...
 
std::string getName () const
 Get the frame name. More...
 
ReferenceFramePtr getParentFrame ()
 get a pointer to this frames parent More...
 
ReferenceFramegetRootFrame ()
 
RobotDynamics::Math::SpatialTransform getTransformFromParent ()
 Get spatial transform from parent to this frame. More...
 
void 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 getTransformToDesiredFrame (ReferenceFramePtr desiredFrame)
 Get the spatial transform from this frame to desiredFrame and store it in transformToPack. More...
 
RobotDynamics::Math::SpatialTransform getTransformToParent ()
 Get spatial transform this frame to its parent. More...
 
virtual RobotDynamics::Math::SpatialTransform getTransformToRoot ()
 Get this frames ReferenceFrame::transformToRoot. More...
 
ReferenceFrameoperator= (const ReferenceFrame &other)
 
 ReferenceFrame (const ReferenceFrame &referenceFrameToCopy)
 Copy constructor. More...
 
 ReferenceFrame (const std::string &frameName, ReferenceFramePtr parentFrame, const RobotDynamics::Math::SpatialTransform &transformFromParent, bool isBodyFrame, unsigned int movableBodyId)
 Constructor. More...
 
 ReferenceFrame ()
 Empty constructor. All contained ptrs will be initialize to nullptr. More...
 
void 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 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 verifyFramesHaveSameRoot (ReferenceFramePtr frame)
 Check if two frames have the same roots. More...
 
virtual ~ReferenceFrame ()
 Destructor. More...
 

Static Public Member Functions

static ReferenceFramePtr createARootFrame (const std::string &frameName)
 Creates a root frame with ReferenceFrame::parentFrame=nullptr. More...
 
static ReferenceFramePtr getWorldFrame ()
 Get a pointer to the world frame. More...
 

Protected Member Functions

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

Static Protected Member Functions

static ReferenceFramePtr createAWorldFrame (const std::string &frameName="world")
 Helper method to create a world frame. More...
 

Protected Attributes

std::string frameName
 
RobotDynamics::Math::SpatialTransform inverseTransformToRoot
 
bool isBodyFrame
 
bool isWorldFrame
 
unsigned int movableBodyId
 
ReferenceFramePtr parentFrame
 
ReferenceFramerootFrame
 
RobotDynamics::Math::SpatialTransform transformFromParent
 
RobotDynamics::Math::SpatialTransform transformToRoot
 

Static Protected Attributes

static ReferenceFramePtr worldFrame = ReferenceFrame::createAWorldFrame()
 

Detailed Description

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.

Definition at line 88 of file ReferenceFrame.hpp.


The documentation for this class was generated from the following files:


rdl_dynamics
Author(s):
autogenerated on Tue Apr 20 2021 02:25:28