Drake
PrismaticJoint Class Reference

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

Inheritance diagram for PrismaticJoint:
Collaboration diagram for PrismaticJoint:

Public Member Functions

 PrismaticJoint (const std::string &name, const Eigen::Isometry3d &transform_to_parent_body, const Eigen::Vector3d &translation_axis)
 
template<typename DerivedQ >
Eigen::Transform< typename DerivedQ::Scalar, 3, Eigen::Isometry > jointTransform (const Eigen::MatrixBase< DerivedQ > &q) const
 
virtual ~PrismaticJoint ()
 
- Public Member Functions inherited from FixedAxisOneDoFJoint< PrismaticJoint >
virtual ~FixedAxisOneDoFJoint ()
 
void motionSubspace (const Eigen::MatrixBase< DerivedQ > &q, Eigen::MatrixBase< DerivedMS > &motion_subspace, typename drake::math::Gradient< DerivedMS, Eigen::Dynamic >::type *dmotion_subspace=nullptr) const
 
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
 
void qdot2v (const Eigen::MatrixBase< DerivedQ > &q, Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic, 0, DrakeJoint::MAX_NUM_VELOCITIES, DrakeJoint::MAX_NUM_POSITIONS > &qdot_to_v, Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic > *dqdot_to_v) const
 
void v2qdot (const Eigen::MatrixBase< DerivedQ > &q, Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic, 0, DrakeJoint::MAX_NUM_POSITIONS, DrakeJoint::MAX_NUM_VELOCITIES > &v_to_qdot, Eigen::Matrix< typename DerivedQ::Scalar, Eigen::Dynamic, Eigen::Dynamic > *dv_to_qdot) const
 
Eigen::Matrix< typename DerivedV::Scalar, Eigen::Dynamic, 1 > frictionTorque (const Eigen::MatrixBase< DerivedV > &v) const
 
void setJointLimits (double joint_limit_min, double joint_limit_max)
 
Eigen::VectorXd zeroConfiguration () const
 
Eigen::VectorXd randomConfiguration (std::default_random_engine &generator) const
 
void setDynamics (double damping, double coulomb_friction, double coulomb_window)
 
virtual std::string getPositionName (int index) const
 
- Public Member Functions inherited from DrakeJointImpl< PrismaticJoint >
 DrakeJointImpl (PrismaticJoint &_derived, const std::string &name, const Eigen::Isometry3d &transform_to_parent_body, int num_positions, int num_velocities)
 
virtual ~DrakeJointImpl ()
 
- Public Member Functions inherited from DrakeJoint
 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 getVelocityName (int index) const
 
virtual bool isFloating () const
 
virtual const Eigen::VectorXd & getJointLimitMin () const
 
virtual const Eigen::VectorXd & getJointLimitMax () const
 

Additional Inherited Members

- Public Types inherited from DrakeJoint
enum  FloatingBaseType { FIXED = 0, ROLLPITCHYAW = 1, QUATERNION = 2 }
 
typedef Eigen::AutoDiffScalar< Eigen::Matrix< double, Eigen::Dynamic, 1, 0, 73, 1 > > AutoDiffFixedMaxSize
 
- Public Attributes inherited from DrakeJoint
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 inherited from DrakeJoint
static const int MAX_NUM_POSITIONS = 7
 
static const int MAX_NUM_VELOCITIES = 6
 
- Protected Member Functions inherited from FixedAxisOneDoFJoint< PrismaticJoint >
 FixedAxisOneDoFJoint (PrismaticJoint &derived, const std::string &name, const Eigen::Isometry3d &transform_to_parent_body, const drake::TwistVector< double > &_joint_axis)
 

Constructor & Destructor Documentation

PrismaticJoint ( const std::string &  name,
const Eigen::Isometry3d &  transform_to_parent_body,
const Eigen::Vector3d &  translation_axis 
)
inline

Here is the call graph for this function:

virtual ~PrismaticJoint ( )
inlinevirtual

Member Function Documentation

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

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