Drake
DrakeJoint Class Referenceabstract

#include <drake/systems/plants/joints/DrakeJoint.h>

Inheritance diagram for DrakeJoint:
Collaboration diagram for DrakeJoint:

Public Types

enum  FloatingBaseType { FIXED = 0, ROLLPITCHYAW = 1, QUATERNION = 2 }
 
typedef Eigen::AutoDiffScalar< Eigen::Matrix< double, Eigen::Dynamic, 1, 0, 73, 1 > > AutoDiffFixedMaxSize
 

Public Member Functions

 DrakeJoint (const std::string &name, const Eigen::Isometry3d &transform_to_parent_body, int num_positions, int num_velocities)
 
virtual ~DrakeJoint ()
 
const Eigen::Isometry3d & getTransformToParentBody () const
 
int getNumPositions () const
 
int getNumVelocities () const
 
const std::string & getName () const
 
virtual std::string getPositionName (int index) const =0
 
virtual std::string getVelocityName (int index) const
 
virtual bool isFloating () const
 
virtual Eigen::VectorXd zeroConfiguration () const =0
 
virtual Eigen::VectorXd randomConfiguration (std::default_random_engine &generator) const =0
 
virtual const Eigen::VectorXd & getJointLimitMin () const
 
virtual const Eigen::VectorXd & getJointLimitMax () const
 

Public Attributes

POSITION_AND_VELOCITY_DEPENDENT_METHODS(Eigen::AutoDiffScalar< Eigen::VectorXd >) EIGEN_MAKE_ALIGNED_OPERATOR_NEW protected Eigen::VectorXd joint_limit_min
 
Eigen::VectorXd joint_limit_max
 

Static Public Attributes

static const int MAX_NUM_POSITIONS = 7
 
static const int MAX_NUM_VELOCITIES = 6
 

Member Typedef Documentation

typedef Eigen::AutoDiffScalar< Eigen::Matrix<double, Eigen::Dynamic, 1, 0, 73, 1> > AutoDiffFixedMaxSize

Member Enumeration Documentation

Enumerator
FIXED 
ROLLPITCHYAW 
QUATERNION 

Constructor & Destructor Documentation

DrakeJoint ( const std::string &  name,
const Eigen::Isometry3d &  transform_to_parent_body,
int  num_positions,
int  num_velocities 
)
~DrakeJoint ( )
virtual

Member Function Documentation

const Eigen::VectorXd & getJointLimitMax ( ) const
virtual

Here is the caller graph for this function:

const Eigen::VectorXd & getJointLimitMin ( ) const
virtual

Here is the caller graph for this function:

const std::string & getName ( ) const

Here is the caller graph for this function:

int getNumPositions ( ) const

Here is the caller graph for this function:

int getNumVelocities ( ) const

Here is the caller graph for this function:

virtual std::string getPositionName ( int  index) const
pure virtual
const Isometry3d & getTransformToParentBody ( ) const

Here is the caller graph for this function:

virtual std::string getVelocityName ( int  index) const
inlinevirtual

Reimplemented in QuaternionFloatingJoint.

Here is the caller graph for this function:

virtual bool isFloating ( ) const
inlinevirtual
virtual Eigen::VectorXd randomConfiguration ( std::default_random_engine &  generator) const
pure virtual
virtual Eigen::VectorXd zeroConfiguration ( ) const
pure virtual

Member Data Documentation

Eigen::VectorXd joint_limit_max
POSITION_AND_VELOCITY_DEPENDENT_METHODS ( Eigen::AutoDiffScalar<Eigen::VectorXd>) EIGEN_MAKE_ALIGNED_OPERATOR_NEW protected Eigen::VectorXd joint_limit_min
const int MAX_NUM_POSITIONS = 7
static
const int MAX_NUM_VELOCITIES = 6
static

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