Drake
RigidBodyFrame Class Reference

#include <drake/systems/plants/RigidBodyFrame.h>

Collaboration diagram for RigidBodyFrame:

Public Member Functions

 RigidBodyFrame (const std::string &_name, RigidBody *_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 *_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...
 
int get_model_id ()
 Returns the ID of the model to which this rigid body frame belongs. More...
 

Public Attributes

std::string name
 
RigidBodybody
 
Eigen::Isometry3d transform_to_body
 
int frame_index = 0
 

Constructor & Destructor Documentation

RigidBodyFrame ( const std::string &  _name,
RigidBody _body,
const Eigen::Isometry3d &  _transform_to_body 
)
inline

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

RigidBodyFrame ( const std::string &  _name,
RigidBody _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.

Member Function Documentation

int get_model_id ( )
inline

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

Member Data Documentation

RigidBody* body
int frame_index = 0
std::string name
Eigen::Isometry3d transform_to_body

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