Drake
FixedJoint Class Reference

#include <drake/multibody/joints/fixed_joint.h>

Inheritance diagram for FixedJoint:
[legend]
Collaboration diagram for FixedJoint:
[legend]

Public Member Functions

 FixedJoint (const std::string &name, const Eigen::Isometry3d &transform_to_parent_body)
 
virtual ~FixedJoint ()
 
template<typename DerivedQ >
Eigen::Transform< typename DerivedQ::Scalar, 3, Eigen::Isometry > jointTransform (const Eigen::MatrixBase< DerivedQ > &q) const
 
template<typename DerivedQ , typename DerivedMS >
void motionSubspace (const Eigen::MatrixBase< DerivedQ > &q, Eigen::MatrixBase< DerivedMS > &motion_subspace, typename drake::math::Gradient< DerivedMS, Eigen::Dynamic >::type *dmotion_subspace=nullptr) const
 
template<typename DerivedQ , typename DerivedV >
void motionSubspaceDotTimesV (const Eigen::MatrixBase< DerivedQ > &q, const Eigen::MatrixBase< DerivedV > &v, Eigen::Matrix< typename DerivedQ::Scalar, 6, 1 > &motion_subspace_dot_times_v, typename drake::math::Gradient< Eigen::Matrix< typename DerivedQ::Scalar, 6, 1 >, Eigen::Dynamic >::type *dmotion_subspace_dot_times_vdq=nullptr, typename drake::math::Gradient< Eigen::Matrix< typename DerivedQ::Scalar, 6, 1 >, Eigen::Dynamic >::type *dmotion_subspace_dot_times_vdv=nullptr) const
 
template<typename DerivedQ >
void qdot2v (const Eigen::MatrixBase< DerivedQ > &q, Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic, 0, MAX_NUM_VELOCITIES, MAX_NUM_POSITIONS > &qdot_to_v, Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic > *dqdot_to_v) const
 
template<typename DerivedQ >
void v2qdot (const Eigen::MatrixBase< DerivedQ > &q, Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic, 0, MAX_NUM_POSITIONS, MAX_NUM_VELOCITIES > &v_to_qdot, Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic > *dv_to_qdot) const
 
template<typename DerivedV >
Eigen::Matrix< typename DerivedV::Scalar, Eigen::Dynamic, 1 > frictionTorque (const Eigen::MatrixBase< DerivedV > &v) const
 
std::string get_position_name (int index) const override
 
Eigen::VectorXd zeroConfiguration () const override
 
Eigen::VectorXd randomConfiguration (std::default_random_engine &generator) const override
 
std::string getPositionName (int index) const override
 

Protected Member Functions

std::unique_ptr< DrakeJointDoClone () const final
 
void DoInitializeClone (DrakeJoint *) const final
 

Constructor & Destructor Documentation

FixedJoint ( const std::string &  name,
const Eigen::Isometry3d &  transform_to_parent_body 
)
inline
virtual ~FixedJoint ( )
inlinevirtual

Member Function Documentation

std::unique_ptr< DrakeJoint > DoClone ( ) const
finalprotected

Here is the caller graph for this function:

void DoInitializeClone ( DrakeJoint ) const
inlinefinalprotected
Eigen::Matrix<typename DerivedV::Scalar, Eigen::Dynamic, 1> frictionTorque ( const Eigen::MatrixBase< DerivedV > &  v) const
inline

Here is the call graph for this function:

std::string get_position_name ( int  index) const
override

Here is the caller graph for this function:

std::string getPositionName ( int  index) const
override

Here is the call graph for this function:

Here is the caller graph for this function:

Eigen::Transform<typename DerivedQ::Scalar, 3, Eigen::Isometry> jointTransform ( const Eigen::MatrixBase< DerivedQ > &  q) const
inline

Here is the call graph for this function:

void motionSubspace ( const Eigen::MatrixBase< DerivedQ > &  q,
Eigen::MatrixBase< DerivedMS > &  motion_subspace,
typename drake::math::Gradient< DerivedMS, Eigen::Dynamic >::type *  dmotion_subspace = nullptr 
) const
inline

Here is the call graph for this function:

void motionSubspaceDotTimesV ( const Eigen::MatrixBase< DerivedQ > &  q,
const Eigen::MatrixBase< DerivedV > &  v,
Eigen::Matrix< typename DerivedQ::Scalar, 6, 1 > &  motion_subspace_dot_times_v,
typename drake::math::Gradient< Eigen::Matrix< typename DerivedQ::Scalar, 6, 1 >, Eigen::Dynamic >::type *  dmotion_subspace_dot_times_vdq = nullptr,
typename drake::math::Gradient< Eigen::Matrix< typename DerivedQ::Scalar, 6, 1 >, Eigen::Dynamic >::type *  dmotion_subspace_dot_times_vdv = nullptr 
) const
inline

Here is the call graph for this function:

void qdot2v ( const Eigen::MatrixBase< DerivedQ > &  q,
Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic, 0, MAX_NUM_VELOCITIES, MAX_NUM_POSITIONS > &  qdot_to_v,
Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic > *  dqdot_to_v 
) const
inline

Here is the call graph for this function:

Eigen::VectorXd randomConfiguration ( std::default_random_engine &  generator) const
override

Here is the caller graph for this function:

void v2qdot ( const Eigen::MatrixBase< DerivedQ > &  q,
Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic, 0, MAX_NUM_POSITIONS, MAX_NUM_VELOCITIES > &  v_to_qdot,
Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic > *  dv_to_qdot 
) const
inline

Here is the call graph for this function:

Eigen::VectorXd zeroConfiguration ( ) const
override

Here is the caller graph for this function:


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