Drake
KinematicsCache< T > Class Template Reference

#include <drake/multibody/kinematics_cache.h>

Public Member Functions

 KinematicsCache (int num_positions, int num_velocities, const std::vector< int > &num_joint_positions, const std::vector< int > &num_joint_velocities)
 Constructor for a KinematicsCache given the number of positions and velocities per body in the vectors num_joint_positions and num_joint_velocities, respectively. More...
 
void CreateCacheElement (int num_positions, int num_velocities)
 Requests a cache entry for a body mobilized by a joint with num_positions and num_velocities. More...
 
const KinematicsCacheElement< T > & get_element (int body_id) const
 Returns constant reference to a cache entry for body body_id. More...
 
KinematicsCacheElement< T > * get_mutable_element (int body_id)
 Returns mutable pointer to a cache entry for body body_id. More...
 
template<typename Derived >
void initialize (const Eigen::MatrixBase< Derived > &q_in)
 
template<typename DerivedQ , typename DerivedV >
void initialize (const Eigen::MatrixBase< DerivedQ > &q_in, const Eigen::MatrixBase< DerivedV > &v_in)
 
void checkCachedKinematicsSettings (bool velocity_kinematics_required, bool jdot_times_v_required, const std::string &method_name) const
 
const Eigen::Matrix< T, Eigen::Dynamic, 1 > & getQ () const
 Returns q, the generalized position vector of the RigidBodyTree that was used to compute this KinematicsCache. More...
 
const Eigen::Matrix< T, Eigen::Dynamic, 1 > & getV () const
 Returns v, the generalized velocity vector of the RigidBodyTree that was used to compute this KinematicsCache. More...
 
Eigen::Matrix< T, Eigen::Dynamic, 1 > getX () const
 Returns x, the state vector of the RigidBodyTree that was used to compute this KinematicsCache. More...
 
bool hasV () const
 Returns true if this KinematicsCache object has a valid v vector. More...
 
void setInertiasCached ()
 
bool areInertiasCached ()
 
void setPositionKinematicsCached ()
 
void setJdotVCached (bool jdotV_cached_in)
 
int get_num_cache_elements () const
 
int get_num_positions () const
 
int getNumPositions () const
 
int get_num_velocities () const
 
int getNumVelocities () const
 

Constructor & Destructor Documentation

KinematicsCache ( int  num_positions,
int  num_velocities,
const std::vector< int > &  num_joint_positions,
const std::vector< int > &  num_joint_velocities 
)

Constructor for a KinematicsCache given the number of positions and velocities per body in the vectors num_joint_positions and num_joint_velocities, respectively.

For a RigidBodyTree with nbodies rigid bodies, num_joint_positions and num_joint_velocities are vectors of size nbodies containing in the i-th entry the number of positions and the number of velocities for the i-th RigidBody in the RigidBodyTree.

Note that you will typically not create a KinematicsCache object using this constructor. Instead, you usually obtain a KinematicsCache object by calling RigidBodyTree::CreateKinematicsCache() or RigidBodyTree::CreateKinematicsCacheWithType(). The second option is useful if you need a particular type for your cache like Eigen::AutoDiffScalar.

For examples on how to create and use the KinematicsCache, see rigid_body_tree_dynamics_test.cc and rigid_body_tree_kinematics_test.cc.

Parameters
num_positionsTotal number of positions in the RigidBodyTree.
num_velocitiesTotal number of velocities in the RigidBodyTree.
num_joint_positionsA std::vector<int> containing in the i-th entry the number of positions for the i-th body in the RigidBodyTree.
num_joint_velocitiesA std::vector<int> containing in the i-th entry the number of velocities for the i-th body in the RigidBodyTree.

Member Function Documentation

bool areInertiasCached ( )

Here is the caller graph for this function:

void checkCachedKinematicsSettings ( bool  velocity_kinematics_required,
bool  jdot_times_v_required,
const std::string &  method_name 
) const

Here is the call graph for this function:

Here is the caller graph for this function:

void CreateCacheElement ( int  num_positions,
int  num_velocities 
)

Requests a cache entry for a body mobilized by a joint with num_positions and num_velocities.

const KinematicsCacheElement< T > & get_element ( int  body_id) const

Returns constant reference to a cache entry for body body_id.

Here is the caller graph for this function:

KinematicsCacheElement< T > * get_mutable_element ( int  body_id)

Returns mutable pointer to a cache entry for body body_id.

Here is the caller graph for this function:

int get_num_cache_elements ( ) const

Here is the caller graph for this function:

int get_num_positions ( ) const

Here is the caller graph for this function:

int get_num_velocities ( ) const

Here is the caller graph for this function:

int getNumPositions ( ) const

Here is the call graph for this function:

int getNumVelocities ( ) const

Here is the call graph for this function:

const Eigen::Matrix< T, Eigen::Dynamic, 1 > & getQ ( ) const

Returns q, the generalized position vector of the RigidBodyTree that was used to compute this KinematicsCache.

Here is the caller graph for this function:

const Eigen::Matrix< T, Eigen::Dynamic, 1 > & getV ( ) const

Returns v, the generalized velocity vector of the RigidBodyTree that was used to compute this KinematicsCache.

Here is the call graph for this function:

Here is the caller graph for this function:

Eigen::Matrix< T, Eigen::Dynamic, 1 > getX ( ) const

Returns x, the state vector of the RigidBodyTree that was used to compute this KinematicsCache.

This is the concatenation of q, the RigidBodyTree's generalized position vector, and v the RigidBodyTree's generalized velocity vector into a single vector. Within x, q precedes v.

Here is the call graph for this function:

bool hasV ( ) const

Returns true if this KinematicsCache object has a valid v vector.

v is the generalized velocity vector of the RigidBodyTree that was used to compute this KinematicsCache.

Here is the caller graph for this function:

void initialize ( const Eigen::MatrixBase< Derived > &  q_in)

Here is the caller graph for this function:

void initialize ( const Eigen::MatrixBase< DerivedQ > &  q_in,
const Eigen::MatrixBase< DerivedV > &  v_in 
)

Here is the call graph for this function:

void setInertiasCached ( )

Here is the caller graph for this function:

void setJdotVCached ( bool  jdotV_cached_in)

Here is the caller graph for this function:

void setPositionKinematicsCached ( )

Here is the caller graph for this function:


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