Drake
KinematicsCache< Scalar > Class Template Reference

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

Public Member Functions

 KinematicsCache (const std::vector< std::unique_ptr< RigidBody > > &bodies)
 
KinematicsCacheElement< Scalar > & getElement (const RigidBody &body)
 
const KinematicsCacheElement< Scalar > & getElement (const RigidBody &body) const
 
template<typename Derived >
void initialize (const Eigen::MatrixBase< Derived > &q)
 
template<typename DerivedQ , typename DerivedV >
void initialize (const Eigen::MatrixBase< DerivedQ > &q, const Eigen::MatrixBase< DerivedV > &v)
 
void checkCachedKinematicsSettings (bool velocity_kinematics_required, bool jdot_times_v_required, const std::string &method_name) const
 
template<typename Derived >
Eigen::Matrix< typename Derived::Scalar, Derived::RowsAtCompileTime, Eigen::Dynamic > transformVelocityMappingToPositionDotMapping (const Eigen::MatrixBase< Derived > &mat) const
 
template<typename Derived >
Eigen::Matrix< typename Derived::Scalar, Derived::RowsAtCompileTime, Eigen::Dynamic > transformPositionDotMappingToVelocityMapping (const Eigen::MatrixBase< Derived > &mat) const
 
const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > & getQ () const
 
const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > & getV () const
 
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > getX () const
 
bool hasV () const
 
void setInertiasCached ()
 
bool areInertiasCached ()
 
void setPositionKinematicsCached ()
 
void setJdotVCached (bool jdotV_cached)
 
int getNumPositions () const
 
int getNumVelocities () const
 

Constructor & Destructor Documentation

KinematicsCache ( const std::vector< std::unique_ptr< RigidBody > > &  bodies)
inlineexplicit

Member Function Documentation

bool areInertiasCached ( )
inline

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
inline

Here is the caller graph for this function:

KinematicsCacheElement<Scalar>& getElement ( const RigidBody body)
inline

Here is the caller graph for this function:

const KinematicsCacheElement<Scalar>& getElement ( const RigidBody body) const
inline
int getNumPositions ( ) const
inline

Here is the caller graph for this function:

int getNumVelocities ( ) const
inline

Here is the caller graph for this function:

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

Here is the caller graph for this function:

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

Here is the caller graph for this function:

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

Here is the caller graph for this function:

bool hasV ( ) const
inline

Here is the caller graph for this function:

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

Here is the caller graph for this function:

void initialize ( const Eigen::MatrixBase< DerivedQ > &  q,
const Eigen::MatrixBase< DerivedV > &  v 
)
inline
void setInertiasCached ( )
inline

Here is the caller graph for this function:

void setJdotVCached ( bool  jdotV_cached)
inline

Here is the caller graph for this function:

void setPositionKinematicsCached ( )
inline

Here is the caller graph for this function:

Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Eigen::Dynamic> transformPositionDotMappingToVelocityMapping ( const Eigen::MatrixBase< Derived > &  mat) const
inline

Here is the caller graph for this function:

Eigen::Matrix<typename Derived::Scalar, Derived::RowsAtCompileTime, Eigen::Dynamic> transformVelocityMappingToPositionDotMapping ( const Eigen::MatrixBase< Derived > &  mat) const
inline

Here is the caller graph for this function:


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