Drake
RigidBodyFrame< T > Class Template Reference

Multibody systems typically have distinguished frames of interest that need to be monitored. More...

#include <drake/multibody/rigid_body_frame.h>

Public Member Functions

 RigidBodyFrame (const std::string &name, RigidBody< T > *body, const Eigen::Isometry3d &transform_to_body)
 A constructor where the transform-to-body is specified using an Eigen::Isometry3d matrix. More...
 
 RigidBodyFrame (const std::string &name, RigidBody< T > *body, const Eigen::Vector3d &xyz=Eigen::Vector3d::Zero(), const Eigen::Vector3d &rpy=Eigen::Vector3d::Zero())
 A constructor where the transform-to-body is specified using Euler angles. More...
 
 RigidBodyFrame ()
 The default constructor. More...
 
virtual ~RigidBodyFrame ()
 
virtual std::shared_ptr< RigidBodyFrame< T > > Clone (RigidBody< T > *body) const
 Returns a clone of this RigidBodyFrame. More...
 
int get_model_instance_id () const
 Returns the ID of the model instance to which this rigid body frame belongs. More...
 
const std::string & get_name () const
 Returns the name of this frame. More...
 
const RigidBody< T > & get_rigid_body () const
 Returns the rigid body to which this frame is attached. More...
 
RigidBody< T > * get_mutable_rigid_body ()
 Returns the rigid body to which this frame is attached. More...
 
const Eigen::Isometry3d & get_transform_to_body () const
 Returns the transform between the coordinate frame that belongs to this RigidBodyFrame and the coordinate frame that belongs to the RigidBody to which this frame is attached (which is obtainable by calling RigidBodyFrame::get_rigid_body()). More...
 
Eigen::Isometry3d * get_mutable_transform_to_body ()
 Returns the transform between the coordinate frame that belongs to this RigidBodyFrame and the coordinate frame that belongs to the RigidBody to which this frame is attached. More...
 
int get_frame_index () const
 Returns the index of this RigidBodyFrame within the vector of RigidBodyFrame objects in the RigidBodyTree. More...
 
void set_name (const std::string &name)
 Sets the name of this RigidBodyFrame. More...
 
void set_rigid_body (RigidBody< T > *rigid_body)
 Sets the rigid body to which this frame is attached. More...
 
bool has_as_rigid_body (RigidBody< T > *rigid_body)
 Returns true if this frame's rigid body is equal to the rigid_body. More...
 
void set_frame_index (int frame_index)
 Sets the index of this frame. More...
 
void set_transform_to_body (const Eigen::Isometry3d &transform_to_body)
 Sets the transform to body of this RigidBodyFrame. More...
 

Detailed Description

template<typename T>
class RigidBodyFrame< T >

Multibody systems typically have distinguished frames of interest that need to be monitored.

A frame is fully described by the body it is rigidly attached to and the pose of this frame with respect to that body. RigidBodyFrame provides an abstraction to describe these frames.

Template Parameters
TThe type being integrated. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T's are provided:

  • double
  • AutoDiffXd
  • AutoDiffUpTo73d

They are already available to link against in the containing library. No other values for T are currently supported.

Constructor & Destructor Documentation

RigidBodyFrame ( const std::string &  name,
RigidBody< T > *  body,
const Eigen::Isometry3d &  transform_to_body 
)

A constructor where the transform-to-body is specified using an Eigen::Isometry3d matrix.

RigidBodyFrame ( const std::string &  name,
RigidBody< T > *  body,
const Eigen::Vector3d &  xyz = Eigen::Vector3d::Zero(),
const Eigen::Vector3d &  rpy = Eigen::Vector3d::Zero() 
)

A constructor where the transform-to-body is specified using Euler angles.

Here is the call graph for this function:

RigidBodyFrame ( )
inline

The default constructor.

virtual ~RigidBodyFrame ( )
inlinevirtual

Member Function Documentation

std::shared_ptr< RigidBodyFrame< T > > Clone ( RigidBody< T > *  body) const
virtual

Returns a clone of this RigidBodyFrame.

It is admittedly awkward for a clone method to have an input parameter. This parameter, however, is necessary to ensure the returned clone is fully initialized.

Parameters
[in]bodyA pointer to the body to include in the returned clone. This pointer must remain valid for the duration of the clone's lifetime.
int get_frame_index ( ) const

Returns the index of this RigidBodyFrame within the vector of RigidBodyFrame objects in the RigidBodyTree.

Here is the caller graph for this function:

int get_model_instance_id ( ) const

Returns the ID of the model instance to which this rigid body frame belongs.

RigidBody< T > * get_mutable_rigid_body ( )

Returns the rigid body to which this frame is attached.

Eigen::Isometry3d * get_mutable_transform_to_body ( )

Returns the transform between the coordinate frame that belongs to this RigidBodyFrame and the coordinate frame that belongs to the RigidBody to which this frame is attached.

const std::string & get_name ( ) const

Returns the name of this frame.

Here is the caller graph for this function:

const RigidBody< T > & get_rigid_body ( ) const

Returns the rigid body to which this frame is attached.

Here is the caller graph for this function:

const Eigen::Isometry3d & get_transform_to_body ( ) const

Returns the transform between the coordinate frame that belongs to this RigidBodyFrame and the coordinate frame that belongs to the RigidBody to which this frame is attached (which is obtainable by calling RigidBodyFrame::get_rigid_body()).

Let B be the coordinate frame of the RigidBody to which this RigidBodyFrame is attached and F be the coordinate frame of this RigidBodyFrame. Furthermore, let p_B be the location of a point measured from B's origin and expressed in coordinate frame B, and p_F be the location of the same point but measured from F's origin and expressed in coordinate frame F.

The returned value is T_BF where:

p_B = T_BF * p_F;

Here is the caller graph for this function:

bool has_as_rigid_body ( RigidBody< T > *  rigid_body)

Returns true if this frame's rigid body is equal to the rigid_body.

void set_frame_index ( int  frame_index)

Sets the index of this frame.

This is the index in the vector of RigidBodyFrames within the RigidBodyTree.

void set_name ( const std::string &  name)

Sets the name of this RigidBodyFrame.

Here is the caller graph for this function:

void set_rigid_body ( RigidBody< T > *  rigid_body)

Sets the rigid body to which this frame is attached.

Parameter rigid_body must remain valid for the lifetime of this RigidBodyFrame object.

void set_transform_to_body ( const Eigen::Isometry3d &  transform_to_body)

Sets the transform to body of this RigidBodyFrame.

This transform must be T_BF as described in method RigidBodyFrame::get_transform_to_body().

See also
RigidBodyFrame::get_transform_to_body

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