Drake
Joint< T > Class Template Referenceabstract

A Joint models the kinematical relationship which characterizes the possible relative motion between two bodies. More...

#include <drake/multibody/tree/multibody_tree.h>

Classes

struct  BluePrint
 (Advanced) Structure containing all the information needed to build the MultibodyTree implementation for a Joint. More...
 
struct  JointImplementation
 (Advanced) A Joint is implemented in terms of MultibodyTree elements such as bodies, mobilizers, force elements and constraints. More...
 

Public Member Functions

 Joint (const std::string &name, const Frame< T > &frame_on_parent, const Frame< T > &frame_on_child, const VectorX< double > &pos_lower_limits, const VectorX< double > &pos_upper_limits, const VectorX< double > &vel_lower_limits, const VectorX< double > &vel_upper_limits, const VectorX< double > &acc_lower_limits, const VectorX< double > &acc_upper_limits)
 Creates a joint between two Frame objects which imposes a given kinematic relation between frame F attached on the parent body P and frame M attached on the child body B. More...
 
virtual ~Joint ()
 
const std::string & name () const
 Returns the name of this joint. More...
 
const Body< T > & parent_body () const
 Returns a const reference to the parent body P. More...
 
const Body< T > & child_body () const
 Returns a const reference to the child body B. More...
 
const Frame< T > & frame_on_parent () const
 Returns a const reference to the frame F attached on the parent body P. More...
 
const Frame< T > & frame_on_child () const
 Returns a const reference to the frame M attached on the child body B. More...
 
int num_dofs () const
 Returns the number of degrees of freedom for this joint. More...
 
int velocity_start () const
 Returns the index to the first generalized velocity for this joint within the vector v of generalized velocities for the full multibody system. More...
 
int num_velocities () const
 Returns the number of generalized velocities describing this joint. More...
 
int position_start () const
 Returns the index to the first generalized position for this joint within the vector q of generalized positions for the full multibody system. More...
 
int num_positions () const
 Returns the number of generalized positions describing this joint. More...
 
const T & GetOnePosition (const systems::Context< T > &context) const
 Returns the position coordinate for joints with a single degree of freedom. More...
 
const T & GetOneVelocity (const systems::Context< T > &context) const
 Returns the velocity coordinate for joints with a single degree of freedom. More...
 
void AddInOneForce (const systems::Context< T > &context, int joint_dof, const T &joint_tau, MultibodyForces< T > *forces) const
 Adds into forces a force along the one of the joint's degrees of freedom indicated by index joint_dof. More...
 
void AddInDamping (const systems::Context< T > &context, MultibodyForces< T > *forces) const
 Adds into forces the force due to damping within this joint. More...
 
Does not allow copy, move, or assignment
 Joint (const Joint &)=delete
 
Jointoperator= (const Joint &)=delete
 
 Joint (Joint &&)=delete
 
Jointoperator= (Joint &&)=delete
 
Methods to get and set the limits of <tt>this</tt> joint. For position

limits, the layout is the same as the generalized position's.

For velocity and acceleration limits, the layout is the same as the generalized velocity's. A limit with value +/- ∞ implies no upper or lower limit.

Returns the position lower limits.

const VectorX< double > & position_lower_limits () const
 
const VectorX< double > & position_upper_limits () const
 Returns the position upper limits. More...
 
const VectorX< double > & velocity_lower_limits () const
 Returns the velocity lower limits. More...
 
const VectorX< double > & velocity_upper_limits () const
 Returns the velocity upper limits. More...
 
const VectorX< double > & acceleration_lower_limits () const
 Returns the acceleration lower limits. More...
 
const VectorX< double > & acceleration_upper_limits () const
 Returns the acceleration upper limits. More...
 
void set_velocity_limits (const VectorX< double > &lower_limits, const VectorX< double > &upper_limits)
 Sets the velocity limits to lower_limits and upper_limits. More...
 
void set_acceleration_limits (const VectorX< double > &lower_limits, const VectorX< double > &upper_limits)
 Sets the acceleration limits to lower_limits and upper_limits. More...
 

Protected Member Functions

virtual int do_get_velocity_start () const =0
 Implementation to the NVI velocity_start(), see velocity_start() for details. More...
 
virtual int do_get_num_velocities () const =0
 Implementation to the NVI num_velocities(), see num_velocities() for details. More...
 
virtual int do_get_position_start () const =0
 Implementation to the NVI position_start(), see position_start() for details. More...
 
virtual int do_get_num_positions () const =0
 Implementation to the NVI num_positions(), see num_positions() for details. More...
 
virtual const T & DoGetOnePosition (const systems::Context< T > &) const
 Implementation to the NVI GetOnePosition() that must only be implemented by those joint subclasses that have a single degree of freedom. More...
 
virtual const T & DoGetOneVelocity (const systems::Context< T > &) const
 Implementation to the NVI GetOneVelocity() that must only be implemented by those joint subclasses that have a single degree of freedom. More...
 
virtual void DoAddInOneForce (const systems::Context< T > &context, int joint_dof, const T &joint_tau, MultibodyForces< T > *forces) const =0
 Adds into forces a force along the one of the joint's degrees of freedom given by joint_dof. More...
 
virtual void DoAddInDamping (const systems::Context< T > &, MultibodyForces< T > *) const
 Adds into MultibodyForces the forces due to damping within this joint. More...
 
void DoSetTopology (const internal::MultibodyTreeTopology &)
 
virtual std::unique_ptr< BluePrintMakeImplementationBlueprint () const =0
 This method must be implemented by derived classes in order to provide JointImplementationBuilder a BluePrint of their internal implementation JointImplementation. More...
 
const JointImplementationget_implementation () const
 Returns a const reference to the internal implementation of this joint. More...
 
Methods to make a clone templated on different scalar types.

Clones this Joint (templated on T) to a joint templated on double.

virtual std::unique_ptr< Joint< double > > DoCloneToScalar (const internal::MultibodyTree< double > &tree_clone) const =0
 
virtual std::unique_ptr< Joint< AutoDiffXd > > DoCloneToScalar (const internal::MultibodyTree< AutoDiffXd > &tree_clone) const =0
 Clones this Joint (templated on T) to a joint templated on AutoDiffXd. More...
 
virtual std::unique_ptr< Joint< symbolic::Expression > > DoCloneToScalar (const internal::MultibodyTree< symbolic::Expression > &) const =0
 

Friends

template<typename >
class Joint
 
class internal::JointImplementationBuilder< T >
 

Detailed Description

template<typename T>
class drake::multibody::Joint< T >

A Joint models the kinematical relationship which characterizes the possible relative motion between two bodies.

The two bodies connected by a Joint object are referred to as the parent and child bodies. Although the terms parent and child are sometimes used synonymously to describe the relationship between inboard and outboard bodies in multibody models, this usage is wholly unrelated and implies nothing about the inboard-outboard relationship between the bodies. A Joint is a model of a physical kinematic constraint between two bodies, a constraint that in the real physical system does not even allude to the ordering of the bodies.

In Drake we define a frame F rigidly attached to the parent body P with pose X_PF and a frame M rigidly attached to the child body B with pose X_BM. A Joint object specifies a kinematic relation between frames F and M, which in turn imposes a kinematic relation between bodies P and B.

Typical joints include the ball joint, to allow unrestricted rotations about a given point, the revolute joint, that constraints two bodies to rotate about a given common axis, etc.

Consider the following example to build a simple pendulum system:

MultibodyTree<double> model;
// ... Code here to setup quantities below as mass, com, etc. ...
const Body<double>& pendulum =
model.AddBody<RigidBody>(SpatialInertia<double>(mass, com, unit_inertia));
// We will connect the pendulum body to the world using a RevoluteJoint.
// In this simple case the parent body P is the model's world body and frame
// F IS the world frame.
// Additionally, we need to specify the pose of frame M on the pendulum's
// body frame B.
// Say we declared and initialized X_BM...
const RevoluteJoint<double>& elbow =
model.AddJoint<RevoluteJoint>(
"Elbow", /* joint name */
model.world_body(), /* parent body */
{}, /* frame F IS the world frame W */
pendulum, /* child body, the pendulum */
X_BM, /* pose of frame M in the body frame B */
Vector3d::UnitZ()); /* revolute axis in this case */
Warning
Do not ever attempt to instantiate and manipulate Joint objects on the stack; it will fail. Add joints to your model using the provided API MultibodyTree::AddJoint() as in the example above.
Template Parameters
TThe scalar type. Must be a valid Eigen scalar.

Constructor & Destructor Documentation

◆ Joint() [1/3]

Joint ( const Joint< T > &  )
delete

◆ Joint() [2/3]

Joint ( Joint< T > &&  )
delete

◆ Joint() [3/3]

Joint ( const std::string &  name,
const Frame< T > &  frame_on_parent,
const Frame< T > &  frame_on_child,
const VectorX< double > &  pos_lower_limits,
const VectorX< double > &  pos_upper_limits,
const VectorX< double > &  vel_lower_limits,
const VectorX< double > &  vel_upper_limits,
const VectorX< double > &  acc_lower_limits,
const VectorX< double > &  acc_upper_limits 
)

Creates a joint between two Frame objects which imposes a given kinematic relation between frame F attached on the parent body P and frame M attached on the child body B.

The joint will be initialized to the model instance from frame_on_child (this is the typical convention for joints between the world and a model, or between two models (e.g. an arm to a gripper)). See this class's documentation for further details.

Parameters
[in]nameA string with a name identifying this joint.
[in]frame_on_parentThe frame F attached on the parent body connected by this joint.
[in]frame_on_childThe frame M attached on the child body connected by this joint.
[in]pos_lower_limitsA vector storing the lower limit for each generalized position. It must have the same size as pos_upper_limit. A value equal to -∞ implies no lower limit.
[in]pos_upper_limitsA vector storing the upper limit for each generalized position. It must have the same size as pos_lower_limit. A value equal to +∞ implies no upper limit.
[in]vel_lower_limitsA vector storing the lower limit for each generalized velocity. It must have the same size as vel_upper_limit. A value equal to -∞ implies no lower limit.
[in]vel_upper_limitsA vector storing the upper limit for each generalized velocity. It must have the same size as vel_lower_limit. A value equal to +∞ implies no upper limit.
[in]acc_lower_limitsA vector storing the lower limit for each generalized acceleration. It must have the same size as acc_upper_limit. A value equal to -∞ implies no lower limit.
[in]acc_upper_limitsA vector storing the upper limit for each generalized acceleration. It must have the same size as acc_lower_limit. A value equal to +∞ implies no upper limit.

◆ ~Joint()

virtual ~Joint ( )
virtual

Member Function Documentation

◆ acceleration_lower_limits()

const VectorX<double>& acceleration_lower_limits ( ) const

Returns the acceleration lower limits.

◆ acceleration_upper_limits()

const VectorX<double>& acceleration_upper_limits ( ) const

Returns the acceleration upper limits.

◆ AddInDamping()

void AddInDamping ( const systems::Context< T > &  context,
MultibodyForces< T > *  forces 
) const

Adds into forces the force due to damping within this joint.

Parameters
[in]contextThe context storing the state and parameters for the model to which this joint belongs.
[out]forcesOn return, this method will add the force due to damping within this joint. This method aborts if forces is nullptr or if forces does not have the right sizes to accommodate a set of forces for the model to which this joint belongs.

◆ AddInOneForce()

void AddInOneForce ( const systems::Context< T > &  context,
int  joint_dof,
const T &  joint_tau,
MultibodyForces< T > *  forces 
) const

Adds into forces a force along the one of the joint's degrees of freedom indicated by index joint_dof.

The meaning for this degree of freedom and even its dimensional units depend on the specific joint sub-class. For a RevoluteJoint for instance, joint_dof can only be 0 since revolute joints's motion subspace only has one degree of freedom, while the units of joint_tau are those of torque (N⋅m in the MKS system of units). For multi-dof joints please refer to the documentation provided by specific joint sub-classes regarding the meaning of joint_dof.

Parameters
[in]contextThe context storing the state and parameters for the model to which this joint belongs.
[in]joint_dofIndex specifying one of the degrees of freedom for this joint. The index must be in the range 0 <= joint_dof < num_velocities() or otherwise this method will abort.
[in]joint_tauGeneralized force corresponding to the degree of freedom indicated by joint_dof to be added into forces.
[out]forcesOn return, this method will add force joint_tau for the degree of freedom joint_dof into the output forces. This method aborts if forces is nullptr or if forces doest not have the right sizes to accommodate a set of forces for the model to which this joint belongs.

◆ child_body()

const Body<T>& child_body ( ) const

Returns a const reference to the child body B.

◆ do_get_num_positions()

virtual int do_get_num_positions ( ) const
protectedpure virtual

Implementation to the NVI num_positions(), see num_positions() for details.

◆ do_get_num_velocities()

virtual int do_get_num_velocities ( ) const
protectedpure virtual

Implementation to the NVI num_velocities(), see num_velocities() for details.

◆ do_get_position_start()

virtual int do_get_position_start ( ) const
protectedpure virtual

Implementation to the NVI position_start(), see position_start() for details.

◆ do_get_velocity_start()

virtual int do_get_velocity_start ( ) const
protectedpure virtual

Implementation to the NVI velocity_start(), see velocity_start() for details.

◆ DoAddInDamping()

virtual void DoAddInDamping ( const systems::Context< T > &  ,
MultibodyForces< T > *   
) const
protectedvirtual

Adds into MultibodyForces the forces due to damping within this joint.

How forces are added to a MultibodyTree model depends on the underlying implementation of a particular joint (for instance, mobilizer vs. constraint) and therefore specific Joint subclasses must provide a definition for this method. The default implementation is a no-op for joints with no damping.

Reimplemented in RevoluteJoint< T >, and PrismaticJoint< T >.

◆ DoAddInOneForce()

virtual void DoAddInOneForce ( const systems::Context< T > &  context,
int  joint_dof,
const T &  joint_tau,
MultibodyForces< T > *  forces 
) const
protectedpure virtual

Adds into forces a force along the one of the joint's degrees of freedom given by joint_dof.

How forces are added to a MultibodyTree model depends on the underlying implementation of a particular joint and therefore specific Joint subclasses must provide a definition for this method. For instance, a revolute joint could be modeled with a single generalized coordinate for the angular rotation (implemented through a RevoluteMobilizer) or it could be modeled using a constraint that only allows rotation about the joint's axis but that constrains the motion in the other five degrees of freedom. This method is only called by the public NVI AddInOneForce() and therefore input arguments were checked to be valid.

See also
The public NVI AddInOneForce() for details.

Implemented in RevoluteJoint< T >, PrismaticJoint< T >, and WeldJoint< T >.

◆ DoCloneToScalar() [1/3]

virtual std::unique_ptr<Joint<double> > DoCloneToScalar ( const internal::MultibodyTree< double > &  tree_clone) const
protectedpure virtual

◆ DoCloneToScalar() [2/3]

virtual std::unique_ptr<Joint<AutoDiffXd> > DoCloneToScalar ( const internal::MultibodyTree< AutoDiffXd > &  tree_clone) const
protectedpure virtual

Clones this Joint (templated on T) to a joint templated on AutoDiffXd.

◆ DoCloneToScalar() [3/3]

virtual std::unique_ptr<Joint<symbolic::Expression> > DoCloneToScalar ( const internal::MultibodyTree< symbolic::Expression > &  ) const
protectedpure virtual

◆ DoGetOnePosition()

virtual const T& DoGetOnePosition ( const systems::Context< T > &  ) const
protectedvirtual

Implementation to the NVI GetOnePosition() that must only be implemented by those joint subclasses that have a single degree of freedom.

The default implementation for all other joints is to abort with an appropriate message. Revolute and prismatic are examples of joints that will want to implement this method.

◆ DoGetOneVelocity()

virtual const T& DoGetOneVelocity ( const systems::Context< T > &  ) const
protectedvirtual

Implementation to the NVI GetOneVelocity() that must only be implemented by those joint subclasses that have a single degree of freedom.

The default implementation for all other joints is to abort with an appropriate message. Revolute and prismatic are examples of joints that will want to implement this method.

◆ DoSetTopology()

void DoSetTopology ( const internal::MultibodyTreeTopology )
protected

◆ frame_on_child()

const Frame<T>& frame_on_child ( ) const

Returns a const reference to the frame M attached on the child body B.

◆ frame_on_parent()

const Frame<T>& frame_on_parent ( ) const

Returns a const reference to the frame F attached on the parent body P.

◆ get_implementation()

const JointImplementation& get_implementation ( ) const
protected

Returns a const reference to the internal implementation of this joint.

Warning
The MultibodyTree model must have already been finalized, or this method will abort.

◆ GetOnePosition()

const T& GetOnePosition ( const systems::Context< T > &  context) const

Returns the position coordinate for joints with a single degree of freedom.

Exceptions
std::exceptionif the joint does not have a single degree of freedom.

◆ GetOneVelocity()

const T& GetOneVelocity ( const systems::Context< T > &  context) const

Returns the velocity coordinate for joints with a single degree of freedom.

Exceptions
std::exceptionif the joint does not have a single degree of freedom.

◆ MakeImplementationBlueprint()

virtual std::unique_ptr<BluePrint> MakeImplementationBlueprint ( ) const
protectedpure virtual

This method must be implemented by derived classes in order to provide JointImplementationBuilder a BluePrint of their internal implementation JointImplementation.

◆ name()

const std::string& name ( ) const

Returns the name of this joint.

◆ num_dofs()

int num_dofs ( ) const

Returns the number of degrees of freedom for this joint.

E.g., one for a revolute joint and three for a ball joint. (Deprecated.)

Deprecated:
"Please use num_velocities()."

◆ num_positions()

int num_positions ( ) const

Returns the number of generalized positions describing this joint.

◆ num_velocities()

int num_velocities ( ) const

Returns the number of generalized velocities describing this joint.

◆ operator=() [1/2]

Joint& operator= ( Joint< T > &&  )
delete

◆ operator=() [2/2]

Joint& operator= ( const Joint< T > &  )
delete

◆ parent_body()

const Body<T>& parent_body ( ) const

Returns a const reference to the parent body P.

◆ position_lower_limits()

const VectorX<double>& position_lower_limits ( ) const

◆ position_start()

int position_start ( ) const

Returns the index to the first generalized position for this joint within the vector q of generalized positions for the full multibody system.

◆ position_upper_limits()

const VectorX<double>& position_upper_limits ( ) const

Returns the position upper limits.

◆ set_acceleration_limits()

void set_acceleration_limits ( const VectorX< double > &  lower_limits,
const VectorX< double > &  upper_limits 
)

Sets the acceleration limits to lower_limits and upper_limits.

Exceptions
std::exceptionif the dimension of lower_limits or upper_limits does not match num_velocities().
std::exceptionif any of lower_limits is larger than the corresponding term in upper_limits.

◆ set_velocity_limits()

void set_velocity_limits ( const VectorX< double > &  lower_limits,
const VectorX< double > &  upper_limits 
)

Sets the velocity limits to lower_limits and upper_limits.

Exceptions
std::exceptionif the dimension of lower_limits or upper_limits does not match num_velocities().
std::exceptionif any of lower_limits is larger than the corresponding term in upper_limits.

◆ velocity_lower_limits()

const VectorX<double>& velocity_lower_limits ( ) const

Returns the velocity lower limits.

◆ velocity_start()

int velocity_start ( ) const

Returns the index to the first generalized velocity for this joint within the vector v of generalized velocities for the full multibody system.

◆ velocity_upper_limits()

const VectorX<double>& velocity_upper_limits ( ) const

Returns the velocity upper limits.

Friends And Related Function Documentation

◆ internal::JointImplementationBuilder< T >

friend class internal::JointImplementationBuilder< T >
friend

◆ Joint

friend class Joint
friend

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