A Joint models the kinematical relationship which characterizes the possible relative motion between two bodies.
The two bodies connected by this Joint object are referred to as parent and child bodies. The parent/child ordering defines the sign conventions for the generalized coordinates and the coordinate ordering for multi-DOF joints. A Joint is a model of a physical kinematic constraint between two bodies, a constraint that in the real physical system does not specify a tree ordering.
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:
T | The scalar type, which must be one of the default scalars. |
#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, typically a Mobilizer. More... | |
Public Member Functions | |
Joint (const std::string &name, const Frame< T > &frame_on_parent, const Frame< T > &frame_on_child, VectorX< double > damping, 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... | |
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) | |
Additional constructor overload for joints with zero damping. More... | |
virtual | ~Joint () |
JointIndex | index () const |
Returns this element's unique index. More... | |
int | ordinal () const |
Returns this element's unique ordinal. More... | |
const std::string & | name () const |
Returns the name of this joint. More... | |
const RigidBody< T > & | parent_body () const |
Returns a const reference to the parent body P. More... | |
const RigidBody< 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... | |
virtual const std::string & | type_name () const =0 |
Returns a string identifying the type of this joint, such as "revolute" or "prismatic". 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... | |
bool | can_rotate () const |
Returns true if this joint's mobility allows relative rotation of the two frames associated with this joint. More... | |
bool | can_translate () const |
Returns true if this joint's mobility allows relative translation of the two frames associated with this joint. More... | |
std::string | position_suffix (int position_index_in_joint) const |
Returns a string suffix (e.g. More... | |
std::string | velocity_suffix (int velocity_index_in_joint) const |
Returns a string suffix (e.g. 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... | |
void | Lock (systems::Context< T > *context) const |
Lock the joint. More... | |
void | Unlock (systems::Context< T > *context) const |
Unlock the joint. More... | |
bool | is_locked (const systems::Context< T > &context) const |
const VectorX< double > & | default_damping_vector () const |
Returns all default damping coefficients for joints that model viscous damping, of size num_velocities(). More... | |
const VectorX< T > & | GetDampingVector (const systems::Context< T > &context) const |
Returns the Context dependent damping coefficients stored as parameters in context . More... | |
void | set_default_damping_vector (const VectorX< double > &damping) |
Sets the default value of the viscous damping coefficients for this joint. More... | |
void | SetDampingVector (systems::Context< T > *context, const VectorX< T > &damping) const |
Sets the value of the viscous damping coefficients for this joint, stored as parameters in context . More... | |
Does not allow copy, move, or assignment | |
Joint (const Joint &)=delete | |
Joint & | operator= (const Joint &)=delete |
Joint (Joint &&)=delete | |
Joint & | operator= (Joint &&)=delete |
Methods to get and set limits | |
For position limits, the layout is the same as the generalized positions q. For velocity and acceleration limits, the layout is the same as the generalized velocities v. A limit with value +/- ∞ implies no upper or lower limit. | |
const VectorX< double > & | position_lower_limits () const |
Returns the position lower limits. More... | |
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_position_limits (const VectorX< double > &lower_limits, const VectorX< double > &upper_limits) |
Sets the position limits to lower_limits and 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... | |
Methods to set and get pose and velocity | |
Joints have both a default state q₀, v₀ (stored here) and a runtime state q, v (stored in a systems::Context). The default state is the value that is used to initialize the runtime state when a Context is first created. (The default velocity v₀ for a joint is always zero so is not settable here.) There are several ways to set these values:
| |
void | set_default_positions (const VectorX< double > &default_positions) |
Sets the default generalized position coordinates q₀ to default_positions . More... | |
const VectorX< double > & | default_positions () const |
Returns the default generalized position coordinates q₀. More... | |
void | SetPositions (systems::Context< T > *context, const Eigen::Ref< const VectorX< T >> &positions) const |
Sets in the given context the generalized position coordinates q for this joint to positions . More... | |
Eigen::Ref< const VectorX< T > > | GetPositions (const systems::Context< T > &context) const |
Returns the current value in the given context of the generalized coordinates q for this joint. More... | |
void | SetVelocities (systems::Context< T > *context, const Eigen::Ref< const VectorX< T >> &velocities) const |
Sets in the given context the generalized velocity coordinates v for this joint to velocities . More... | |
Eigen::Ref< const VectorX< T > > | GetVelocities (const systems::Context< T > &context) const |
Returns the current value in the given context of the generalized velocities v for this joint. More... | |
void | SetDefaultPose (const math::RigidTransform< double > &X_FM) |
Sets this joint's default generalized positions q₀ such that the pose of the child frame M in the parent frame F best matches the given pose. More... | |
math::RigidTransform< double > | GetDefaultPose () const |
Returns this joint's default pose as a RigidTransform X_FM. More... | |
void | SetPose (systems::Context< T > *context, const math::RigidTransform< T > &X_FM) const |
Sets in the given context this joint's generalized positions q such that the pose of the child frame M in the parent frame F best matches the given pose. More... | |
math::RigidTransform< T > | GetPose (const systems::Context< T > &context) const |
Returns this joint's current pose using its position coordinates q taken from the given context and converting that to a RigidTransform X_FM(q). More... | |
void | SetSpatialVelocity (systems::Context< T > *context, const SpatialVelocity< T > &V_FM) const |
Sets in the given context this joint's generalized velocities v such that the spatial velocity of the child frame M in the parent frame F best matches the given spatial velocity. More... | |
SpatialVelocity< T > | GetSpatialVelocity (const systems::Context< T > &context) const |
Given the generalized positions q and generalized velocities v for this joint in the given context , returns the cross-joint spatial velocity V_FM. More... | |
void | SetDefaultPosePair (const Quaternion< double > &q_FM, const Vector3< double > &p_FM) |
(Advanced) This is the same as SetDefaultPose() except it takes the pose as a (quaternion, translation vector) pair. More... | |
std::pair< Eigen::Quaternion< double >, Vector3< double > > | GetDefaultPosePair () const |
(Advanced) This is the same as GetDefaultPose() except it returns this joint's default pose as a (quaternion, translation vector) pair. More... | |
void | SetPosePair (systems::Context< T > *context, const Quaternion< T > &q_FM, const Vector3< T > &p_FM) const |
(Advanced) This is the same as SetPose() except it takes the pose as a (quaternion, translation vector) pair. More... | |
std::pair< Eigen::Quaternion< T >, Vector3< T > > | GetPosePair (const systems::Context< T > &context) const |
(Advanced) This is the same as GetPose() except it returns this joint's pose in the given context as a (quaternion, translation vector) pair. More... | |
Public Member Functions inherited from MultibodyElement< T > | |
virtual | ~MultibodyElement () |
ModelInstanceIndex | model_instance () const |
Returns the ModelInstanceIndex of the model instance to which this element belongs. More... | |
template<typename = void> | |
const MultibodyPlant< T > & | GetParentPlant () const |
Returns the MultibodyPlant that owns this MultibodyElement. More... | |
void | DeclareParameters (internal::MultibodyTreeSystem< T > *tree_system) |
Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time. More... | |
void | SetDefaultParameters (systems::Parameters< T > *parameters) const |
Sets default values of parameters belonging to each MultibodyElement in parameters at a call to MultibodyTreeSystem::SetDefaultParameters(). More... | |
MultibodyElement (const MultibodyElement &)=delete | |
MultibodyElement & | operator= (const MultibodyElement &)=delete |
MultibodyElement (MultibodyElement &&)=delete | |
MultibodyElement & | operator= (MultibodyElement &&)=delete |
Protected Member Functions | |
virtual int | do_get_velocity_start () const =0 |
Implementation of the NVI velocity_start(), see velocity_start() for details. More... | |
virtual int | do_get_num_velocities () const =0 |
Implementation of the NVI num_velocities(), see num_velocities() for details. More... | |
virtual int | do_get_position_start () const =0 |
Implementation of the NVI position_start(), see position_start() for details. More... | |
virtual int | do_get_num_positions () const =0 |
Implementation of the NVI num_positions(), see num_positions() for details. More... | |
virtual std::string | do_get_position_suffix (int index) const =0 |
Implementation of the NVI position_suffix(), see position_suffix() for details. More... | |
virtual std::string | do_get_velocity_suffix (int index) const =0 |
Implementation of the NVI velocity_suffix(), see velocity_suffix() for details. More... | |
virtual void | do_set_default_positions (const VectorX< double > &default_positions)=0 |
Implementation of the NVI set_default_positions(), see set_default_positions() for details. More... | |
virtual void | DoSetDefaultPosePair (const Quaternion< double > &q_FM, const Vector3< double > &p_FM) |
Implementation of the NVI SetDefaultPose(). More... | |
virtual std::pair< Eigen::Quaternion< double >, Vector3< double > > | DoGetDefaultPosePair () const |
Implementation of the NVI GetDefaultPose(). More... | |
virtual const T & | DoGetOnePosition (const systems::Context< T > &) const |
Implementation of 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 of 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 &) override |
Implementation of the NVI SetTopology(). More... | |
virtual std::unique_ptr< BluePrint > | MakeImplementationBlueprint (const internal::SpanningForest::Mobod &mobod) const =0 |
This method must be implemented by derived classes in order to provide JointImplementationBuilder a BluePrint of their internal implementation JointImplementation. More... | |
const JointImplementation & | get_implementation () const |
Returns a const reference to the internal implementation of this joint. More... | |
bool | has_implementation () const |
Returns whether this joint owns a particular implementation. More... | |
std::pair< const Frame< T > *, const Frame< T > * > | tree_frames (bool use_reversed_mobilizer) const |
Utility for concrete joint implementations to use to select the inboard/outboard frames for a tree in the spanning forest, given whether they should be reversed from the parent/child frames that are members of this Joint object. More... | |
template<template< typename > class ConcreteMobilizer> | |
const ConcreteMobilizer< T > & | get_mobilizer_downcast () const |
(Internal use only) Returns the mobilizer implementing this joint, downcast to its specific type. More... | |
template<template< typename > class ConcreteMobilizer> | |
ConcreteMobilizer< T > & | get_mutable_mobilizer_downcast () |
(Internal use only) Mutable flavor of get_mobilizer_downcast(). More... | |
Methods to make a clone templated on different scalar types. | |
Clones this Joint (templated on T) to a joint templated on | |
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 |
Protected Member Functions inherited from MultibodyElement< T > | |
MultibodyElement () | |
Default constructor made protected so that sub-classes can still declare their default constructors if they need to. More... | |
MultibodyElement (ModelInstanceIndex model_instance) | |
Constructor which allows specifying a model instance. More... | |
MultibodyElement (ModelInstanceIndex model_instance, int64_t index) | |
Both the model instance and element index are specified. More... | |
template<typename ElementIndexType > | |
ElementIndexType | index_impl () const |
Returns this element's unique index. More... | |
int | ordinal_impl () const |
Returns this element's unique ordinal. More... | |
const internal::MultibodyTree< T > & | get_parent_tree () const |
Returns a constant reference to the parent MultibodyTree that owns this element. More... | |
const internal::MultibodyTreeSystem< T > & | GetParentTreeSystem () const |
Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element. More... | |
void | SetTopology (const internal::MultibodyTreeTopology &tree) |
Gives MultibodyElement-derived objects the opportunity to retrieve their topology after MultibodyTree::Finalize() is invoked. More... | |
systems::NumericParameterIndex | DeclareNumericParameter (internal::MultibodyTreeSystem< T > *tree_system, const systems::BasicVector< T > &model_vector) |
To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters(). More... | |
systems::AbstractParameterIndex | DeclareAbstractParameter (internal::MultibodyTreeSystem< T > *tree_system, const AbstractValue &model_value) |
To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters(). More... | |
Friends | |
template<typename > | |
class | Joint |
class | internal::JointImplementationBuilder< T > |
Joint | ( | const std::string & | name, |
const Frame< T > & | frame_on_parent, | ||
const Frame< T > & | frame_on_child, | ||
VectorX< double > | damping, | ||
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 assigned 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.
[in] | name | A string with a name identifying this joint. |
[in] | frame_on_parent | The frame F attached on the parent body connected by this joint. |
[in] | frame_on_child | The frame M attached on the child body connected by this joint. |
[in] | damping | A vector of viscous damping coefficients, of size num_velocities(). See default_damping_vector() for details. |
[in] | pos_lower_limits | A 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_limits | A 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_limits | A 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_limits | A 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_limits | A 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_limits | A 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 | ( | 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 | ||
) |
Additional constructor overload for joints with zero damping.
Refer to the more general constructor signature taking damping for further details on the rest of the arguments for this constructor.
|
virtual |
void AddInDamping | ( | const systems::Context< T > & | context, |
MultibodyForces< T > * | forces | ||
) | const |
Adds into forces
the force due to damping within this
joint.
[in] | context | The context storing the state and parameters for the model to which this joint belongs. |
[out] | forces | On 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. |
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
.
[in] | context | The context storing the state and parameters for the model to which this joint belongs. |
[in] | joint_dof | Index 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_tau | Generalized force corresponding to the degree of freedom indicated by joint_dof to be added into forces . |
[out] | forces | On 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. |
bool can_rotate | ( | ) | const |
Returns true if this joint's mobility allows relative rotation of the two frames associated with this joint.
bool can_translate | ( | ) | const |
Returns true if this joint's mobility allows relative translation of the two frames associated with this joint.
const RigidBody<T>& child_body | ( | ) | const |
Returns a const reference to the child body B.
Returns all default damping coefficients for joints that model viscous damping, of size num_velocities().
Joints that do not model damping return a zero vector of size num_velocities(). If vj is the vector of generalized velocities for this joint, of size num_velocities(), viscous damping models a generalized force at the joint of the form tau = -diag(dj)⋅vj, with dj the vector returned by this function. The units of the coefficients will depend on the specific joint type. For instance, for a revolute joint where vj is an angular velocity with units of rad/s and tau having units of N⋅m, the coefficient of viscous damping has units of N⋅m⋅s. Refer to each joint's documentation for further details.
Returns the default generalized position coordinates q₀.
These will be the values set with set_default_positions() if any; otherwise, they will be the "zero configuration" for this joint type (as defined by the particular joint type).
|
protectedpure virtual |
Implementation of the NVI num_positions(), see num_positions() for details.
|
protectedpure virtual |
Implementation of the NVI num_velocities(), see num_velocities() for details.
|
protectedpure virtual |
Implementation of the NVI position_start(), see position_start() for details.
|
protectedpure virtual |
Implementation of the NVI position_suffix(), see position_suffix() for details.
The suffix should contain only alphanumeric characters (e.g. 'wx' not '_wx' or '.wx').
|
protectedpure virtual |
Implementation of the NVI velocity_start(), see velocity_start() for details.
Note that this must be the offset within just the velocity vector, not within the composite state vector.
|
protectedpure virtual |
Implementation of the NVI velocity_suffix(), see velocity_suffix() for details.
The suffix should contain only alphanumeric characters (e.g. 'wx' not '_wx' or '.wx').
|
protectedpure virtual |
Implementation of the NVI set_default_positions(), see set_default_positions() for details.
It is the responsibility of the subclass to ensure that its joint implementation (i.e., mobilizer), should it have one, is updated with default_positions
. Note that the Joint base class also stores default_positions (as a VectorX); the implementing mobilizer should have the same value but as a fixed-size vector.
|
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 QuaternionFloatingJoint< T >, RpyFloatingJoint< T >, RevoluteJoint< T >, PrismaticJoint< T >, BallRpyJoint< T >, and UniversalJoint< T >.
|
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.
Implemented in QuaternionFloatingJoint< T >, RpyFloatingJoint< T >, RevoluteJoint< T >, PrismaticJoint< T >, BallRpyJoint< T >, UniversalJoint< T >, and WeldJoint< T >.
|
protectedpure virtual |
|
protectedpure virtual |
Clones this Joint (templated on T) to a joint templated on AutoDiffXd.
|
protectedpure virtual |
|
protectedvirtual |
Implementation of the NVI GetDefaultPose().
This is optional for Joint subclasses except for floating (6 dof) Joints. The subclass should convert its default_positions to pose X_FM and return that as a (quaternion, translation) pair. If the subclass already uses (quaternion, translation) as generalized coordinates (i.e. it's a quaternion_floating_joint) it must return those exactly (don't convert to a transform first).
|
protectedvirtual |
Implementation of 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.
|
protectedvirtual |
Implementation of 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.
|
protectedvirtual |
Implementation of the NVI SetDefaultPose().
This is optional for Joint subclasses except for floating (6 dof) Joints. The subclass should convert the input to the closest equivalent in generalized coordinates and invoke set_default_positions() to record them. If the subclass already uses (quaternion, translation) as generalized coordinates (i.e. it's a quaternion_floating_joint) it must store those exactly.
|
overrideprotectedvirtual |
Implementation of the NVI SetTopology().
For advanced use only for developers implementing new MultibodyTree components.
Implements MultibodyElement< T >.
const Frame<T>& frame_on_child | ( | ) | const |
Returns a const reference to the frame M attached on the child body B.
const Frame<T>& frame_on_parent | ( | ) | const |
Returns a const reference to the frame F attached on the parent body P.
|
protected |
Returns a const reference to the internal implementation of this
joint.
|
protected |
(Internal use only) Returns the mobilizer implementing this joint, downcast to its specific type.
|
protected |
(Internal use only) Mutable flavor of get_mobilizer_downcast().
const VectorX<T>& GetDampingVector | ( | const systems::Context< T > & | context | ) | const |
Returns the Context dependent damping coefficients stored as parameters in context
.
Refer to default_damping_vector() for details.
[in] | context | The context storing the state and parameters for the model to which this joint belongs. |
math::RigidTransform<double> GetDefaultPose | ( | ) | const |
Returns this joint's default pose as a RigidTransform X_FM.
std::exception | if called for any joint type that does not implement this function. |
X_FM | The default pose as a rigid transform. |
(Advanced) This is the same as GetDefaultPose() except it returns this joint's default pose as a (quaternion, translation vector) pair.
q_FM,p_FM | The default pose as a (quaternion, translation) pair. |
std::exception | if called for any joint type that does not implement this function. |
const T& GetOnePosition | ( | const systems::Context< T > & | context | ) | const |
Returns the position coordinate for joints with a single degree of freedom.
std::exception | if the joint does not have a single degree of freedom. |
const T& GetOneVelocity | ( | const systems::Context< T > & | context | ) | const |
Returns the velocity coordinate for joints with a single degree of freedom.
std::exception | if the joint does not have a single degree of freedom. |
math::RigidTransform<T> GetPose | ( | const systems::Context< T > & | context | ) | const |
Returns this joint's current pose using its position coordinates q taken from the given context
and converting that to a RigidTransform X_FM(q).
std::exception | if called for any joint type that does not implement this function. |
X_FM | The current pose as a rigid transform. |
std::pair<Eigen::Quaternion<T>, Vector3<T> > GetPosePair | ( | const systems::Context< T > & | context | ) | const |
(Advanced) This is the same as GetPose() except it returns this joint's pose in the given context
as a (quaternion, translation vector) pair.
q_FM,p_FM | The pose as a (quaternion, translation) pair. |
std::exception | if the containing MultibodyPlant has not yet been finalized. |
Eigen::Ref<const VectorX<T> > GetPositions | ( | const systems::Context< T > & | context | ) | const |
Returns the current value in the given context
of the generalized coordinates q for this joint.
std::exception | if the containing MultibodyPlant has not yet been finalized. |
SpatialVelocity<T> GetSpatialVelocity | ( | const systems::Context< T > & | context | ) | const |
Given the generalized positions q and generalized velocities v for this joint in the given context
, returns the cross-joint spatial velocity V_FM.
V_FM | the spatial velocity across this joint. |
std::exception | if the containing MultibodyPlant has not yet been finalized. |
Eigen::Ref<const VectorX<T> > GetVelocities | ( | const systems::Context< T > & | context | ) | const |
Returns the current value in the given context
of the generalized velocities v for this joint.
std::exception | if the containing MultibodyPlant has not yet been finalized. |
|
protected |
Returns whether this
joint owns a particular implementation.
If the MultibodyTree has been finalized, this will return true.
JointIndex index | ( | ) | const |
Returns this element's unique index.
bool is_locked | ( | const systems::Context< T > & | context | ) | const |
void Lock | ( | systems::Context< T > * | context | ) | const |
Lock the joint.
Its generalized velocities will be 0 until it is unlocked.
|
protectedpure virtual |
This method must be implemented by derived classes in order to provide JointImplementationBuilder a BluePrint of their internal implementation JointImplementation.
const std::string& name | ( | ) | const |
Returns the name of this joint.
int num_positions | ( | ) | const |
Returns the number of generalized positions describing this joint.
int num_velocities | ( | ) | const |
Returns the number of generalized velocities describing this joint.
int ordinal | ( | ) | const |
Returns this element's unique ordinal.
The joint's ordinal is a unique index into contiguous containers that have an entry for each Joint, such as the vector valued reaction forces (see MultibodyPlant::get_reaction_forces_output_port()). The ordinal value will be updated (if needed) when joints are removed from the parent plant so that the set of ordinal values is a bijection with [0, num_joints()). Ordinals are assigned in the order that joints are added to the plant, thus a set of joints sorted by ordinal has the same ordering as if it were sorted by JointIndex. If joints have been removed from the plant, do not use index() to access contiguous containers with entries per Joint.
const RigidBody<T>& parent_body | ( | ) | const |
Returns a const reference to the parent body P.
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.
std::string position_suffix | ( | int | position_index_in_joint | ) | const |
Returns a string suffix (e.g.
to be appended to the name()) to identify the k
th position in this joint. position_index_in_joint
must be in [0, num_positions()).
void set_acceleration_limits | ( | const VectorX< double > & | lower_limits, |
const VectorX< double > & | upper_limits | ||
) |
Sets the acceleration limits to lower_limits
and upper_limits
.
std::exception | if the dimension of lower_limits or upper_limits does not match num_velocities(). |
std::exception | if any of lower_limits is larger than the corresponding term in upper_limits . |
Sets the default value of the viscous damping coefficients for this joint.
Refer to default_damping_vector() for details.
std::exception | if damping.size() != num_velocities(). |
std::exception | if any of the damping coefficients is negative. |
Sets the default generalized position coordinates q₀ to default_positions
.
default_positions
are NOT constrained to be within position_lower_limits() and position_upper_limits(). std::exception | if the dimension of default_positions does not match num_positions(). |
void set_position_limits | ( | const VectorX< double > & | lower_limits, |
const VectorX< double > & | upper_limits | ||
) |
Sets the position limits to lower_limits
and upper_limits
.
std::exception | if the dimension of lower_limits or upper_limits does not match num_positions(). |
std::exception | if any of lower_limits is larger than the corresponding term in upper_limits . |
default_positions()
, regardless of whether the current default_positions()
satisfy the new position 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
.
std::exception | if the dimension of lower_limits or upper_limits does not match num_velocities(). |
std::exception | if any of lower_limits is larger than the corresponding term in upper_limits . |
void SetDampingVector | ( | systems::Context< T > * | context, |
const VectorX< T > & | damping | ||
) | const |
Sets the value of the viscous damping coefficients for this joint, stored as parameters in context
.
Refer to default_damping_vector() for details.
[out] | context | The context storing the state and parameters for the model to which this joint belongs. |
[in] | damping | The vector of damping values. |
std::exception | if damping.size() != num_velocities(). |
std::exception | if any of the damping coefficients is negative. |
angular_damping = damping[0]
and translational_damping = damping[3]
. Refer to the particular subclass for more semantic information. void SetDefaultPose | ( | const math::RigidTransform< double > & | X_FM | ) |
Sets this joint's default generalized positions q₀ such that the pose of the child frame M in the parent frame F best matches the given pose.
The pose is given by a RigidTransform X_FM
, but a joint will represent pose differently.
std::exception | if called for any joint type that does not implement this function. |
void SetDefaultPosePair | ( | const Quaternion< double > & | q_FM, |
const Vector3< double > & | p_FM | ||
) |
(Advanced) This is the same as SetDefaultPose() except it takes the pose as a (quaternion, translation vector) pair.
A QuaternionFloatingJoint will store this pose bit-identically; an RpyFloatingJoint will store it to within floating point precision; any other joint will approximate it consistent with that joint's mobility.
std::exception | if called for any joint type that does not implement this function. |
void SetPose | ( | systems::Context< T > * | context, |
const math::RigidTransform< T > & | X_FM | ||
) | const |
Sets in the given context
this joint's generalized positions q such that the pose of the child frame M in the parent frame F best matches the given pose.
The pose is given by a RigidTransform X_FM, but a joint will represent pose differently. Drake's "floating" (6 dof) joints can represent any pose, but other joints may only be able to approximate X_FM. See the individual joint descriptions for specifics.
std::exception | if called for any joint type that does not implement this function. |
std::exception | if the containing MultibodyPlant has not yet been finalized. |
context
is not null. void SetPosePair | ( | systems::Context< T > * | context, |
const Quaternion< T > & | q_FM, | ||
const Vector3< T > & | p_FM | ||
) | const |
(Advanced) This is the same as SetPose() except it takes the pose as a (quaternion, translation vector) pair.
A QuaternionFloatingJoint will store this pose bit-identically; any other joint will approximate it.
std::exception | if called for any joint type that does not implement this function. |
std::exception | if the containing MultibodyPlant has not yet been finalized. |
context
is not null. void SetPositions | ( | systems::Context< T > * | context, |
const Eigen::Ref< const VectorX< T >> & | positions | ||
) | const |
Sets in the given context
the generalized position coordinates q for this joint to positions
.
positions
are NOT constrained to be within position_lower_limits() and position_upper_limits(). std::exception | if the dimension of positions does not match num_positions(). |
std::exception | if the containing MultibodyPlant has not yet been finalized. |
context
is not null. void SetSpatialVelocity | ( | systems::Context< T > * | context, |
const SpatialVelocity< T > & | V_FM | ||
) | const |
Sets in the given context
this joint's generalized velocities v such that the spatial velocity of the child frame M in the parent frame F best matches the given spatial velocity.
The velocity is provided as a spatial velocity V_FM, but a joint may represent velocity differently. Drake's "floating" (6 dof) joints can represent any spatial velocity, but other joints may only be able to approximate V_FM. See the individual joint descriptions for specifics.
std::exception | if called for any joint type that does not implement this function. |
std::exception | if the containing MultibodyPlant has not yet been finalized. |
context
is not null. void SetVelocities | ( | systems::Context< T > * | context, |
const Eigen::Ref< const VectorX< T >> & | velocities | ||
) | const |
Sets in the given context
the generalized velocity coordinates v for this joint to velocities
.
velocities
are NOT constrained to be within velocity_lower_limits() and velocity_upper_limits(). std::exception | if the dimension of velocities does not match num_velocities(). |
std::exception | if the containing MultibodyPlant has not yet been finalized. |
context
is not null.
|
protected |
Utility for concrete joint implementations to use to select the inboard/outboard frames for a tree in the spanning forest, given whether they should be reversed from the parent/child frames that are members of this Joint object.
|
pure virtual |
Returns a string identifying the type of this
joint, such as "revolute" or "prismatic".
Implemented in ScrewJoint< T >, RevoluteJoint< T >, QuaternionFloatingJoint< T >, RpyFloatingJoint< T >, UniversalJoint< T >, PlanarJoint< T >, BallRpyJoint< T >, PrismaticJoint< T >, and WeldJoint< T >.
void Unlock | ( | systems::Context< T > * | context | ) | const |
Unlock the joint.
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.
std::string velocity_suffix | ( | int | velocity_index_in_joint | ) | const |
Returns a string suffix (e.g.
to be appended to the name()) to identify the k
th velocity in this joint. velocity_index_in_joint
must be in [0, num_velocities()).
|
friend |
|
friend |