Drake
Drake C++ Documentation
UniversalJoint< T > Class Template Referencefinal

Detailed Description

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

This joint models a universal joint allowing two bodies to rotate relative to one another with two degrees of freedom.

A universal joint can be thought of as a mechanism consisting of three bodies; the parent body P, an intermediate cross-shaped body I, and the child body B. In a physical universal joint, body I has a significantly smaller mass than P or B. This universal joint model corresponds to the mathematical limit of having a body I of negligible mass. Given a frame F attached to the parent body P and a frame M attached to the child body B (see the Joint class's documentation), the orientation of M in F can then naturally be defined as follows using a body fixed rotation sequence. A first rotation of θ₁ about Fx defines the orientation R_FI of the intermediate frame I attached to body I (notice that by definition Ix = Fx at all times). A second rotation of θ₂ about Iy defines the orientation R_IM of frame M (notice that by definition My = Iy at all times). Mathematically, the orientation of frame M in F is given by

  R_FM(q) = R_FI(θ₁) * R_IM(θ₂)

No translational motion of M in F is allowed and the origins, Mo and Fo, of frames M and F respectively remain coincident. The angles of rotation about F's x-axis and M's y-axis, along with their rates, specify the state of the joint. Zero θ₁, θ₂ angles corresponds to frames F, I, and M being coincident. Angles (θ₁, θ₂) are defined to be positive according to the right-hand-rule with the thumb aligned in the direction of their respective axes.

Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Types

template<typename Scalar >
using Context = systems::Context< Scalar >
 

Public Member Functions

 UniversalJoint (const std::string &name, const Frame< T > &frame_on_parent, const Frame< T > &frame_on_child, double damping=0)
 Constructor to create a universal joint between two bodies so that frame F attached to the parent body P and frame M attached to the child body B rotate as described in the class's documentation. More...
 
 ~UniversalJoint () override
 
const std::string & type_name () const override
 Returns a string identifying the type of this joint, such as "revolute" or "prismatic". More...
 
double default_damping () const
 Returns this joint's default damping constant in N⋅m⋅s. More...
 
Vector2< doubleget_default_angles () const
 Gets the default angles for this joint. More...
 
void set_default_angles (const Vector2< double > &angles)
 Sets the default angles of this joint. More...
 
void set_random_angles_distribution (const Vector2< symbolic::Expression > &angles)
 Sets the random distribution that angles of this joint will be randomly sampled from. More...
 
Does not allow copy, move, or assignment
 UniversalJoint (const UniversalJoint &)=delete
 
UniversalJointoperator= (const UniversalJoint &)=delete
 
 UniversalJoint (UniversalJoint &&)=delete
 
UniversalJointoperator= (UniversalJoint &&)=delete
 
Context-dependent value access
Vector2< T > get_angles (const Context< T > &context) const
 Gets the rotation angles of this joint from context. More...
 
const UniversalJoint< T > & set_angles (Context< T > *context, const Vector2< T > &angles) const
 Sets the context so that the generalized coordinates corresponding to the rotation angles of this joint equals angles. More...
 
Vector2< T > get_angular_rates (const systems::Context< T > &context) const
 Gets the rates of change, in radians per second, of this joint's angles (see class documentation) from context. More...
 
const UniversalJoint< T > & set_angular_rates (systems::Context< T > *context, const Vector2< T > &theta_dot) const
 Sets the rates of change, in radians per second, of this this joint's angles (see class documentation) to theta_dot. More...
 
- Public Member Functions inherited from Joint< 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. 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...
 
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...
 
 Joint (const Joint &)=delete
 
Jointoperator= (const Joint &)=delete
 
 Joint (Joint &&)=delete
 
Jointoperator= (Joint &&)=delete
 
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...
 
const VectorX< double > & default_positions () const
 Returns the default positions. 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...
 
void set_default_positions (const VectorX< double > &default_positions)
 Sets the default positions to default_positions. 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< doubleGetDefaultPose () const
 Returns this Joint's default pose as a RigidTransform X_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...
 
- 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 MultibodyPlantDeferred = MultibodyPlant<T>>
const MultibodyPlantDeferred & 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
 
MultibodyElementoperator= (const MultibodyElement &)=delete
 
 MultibodyElement (MultibodyElement &&)=delete
 
MultibodyElementoperator= (MultibodyElement &&)=delete
 

Static Public Attributes

static const char kTypeName [] = "universal"
 The name for this Joint type. It resolves to "universal". More...
 

Protected Member Functions

void DoAddInOneForce (const systems::Context< T > &, int joint_dof, const T &joint_tau, MultibodyForces< T > *forces) const override
 Joint<T> override called through public NVI, Joint::AddInForce(). More...
 
void DoAddInDamping (const systems::Context< T > &context, MultibodyForces< T > *forces) const override
 Joint<T> override called through public NVI, Joint::AddInDamping(). More...
 
- Protected Member Functions inherited from Joint< T >
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...
 
void DoSetTopology (const internal::MultibodyTreeTopology &) override
 Implementation of the NVI SetTopology(). More...
 
const JointImplementationget_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...
 
- 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 UniversalJoint
 

Member Typedef Documentation

◆ Context

using Context = systems::Context<Scalar>

Constructor & Destructor Documentation

◆ UniversalJoint() [1/3]

UniversalJoint ( const UniversalJoint< T > &  )
delete

◆ UniversalJoint() [2/3]

UniversalJoint ( UniversalJoint< T > &&  )
delete

◆ UniversalJoint() [3/3]

UniversalJoint ( const std::string &  name,
const Frame< T > &  frame_on_parent,
const Frame< T > &  frame_on_child,
double  damping = 0 
)

Constructor to create a universal joint between two bodies so that frame F attached to the parent body P and frame M attached to the child body B rotate as described in the class's documentation.

See class documentation for details on the angles defining orientation. This constructor signature creates a joint with no joint limits, i.e. the joint position, velocity and acceleration limits are the pair (-∞, ∞). These can be set using the Joint methods set_position_limits(), set_velocity_limits() and set_acceleration_limits(). The first three arguments to this constructor are those of the Joint class constructor. See the Joint class's documentation for details. The additional parameters are:

Parameters
[in]dampingViscous damping coefficient, in N⋅m⋅s, used to model losses within the joint. See documentation of default_damping() for details on modelling of the damping torque.
Exceptions
std::exceptionif damping is negative.

◆ ~UniversalJoint()

~UniversalJoint ( )
override

Member Function Documentation

◆ default_damping()

double default_damping ( ) const

Returns this joint's default damping constant in N⋅m⋅s.

The damping torque (in N⋅m) is modeled as τᵢ = -damping⋅ωᵢ, i = 1, 2 i.e. opposing motion, with ωᵢ the angular rates about the i-th axis for this joint (see get_angular_rates())and τᵢ the torque on child body B about the same i-th axis.

◆ DoAddInDamping()

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

Joint<T> override called through public NVI, Joint::AddInDamping().

Therefore arguments were already checked to be valid. This method adds into forces a dissipative torque according to the viscous law τ = -d⋅ω, with d the damping coefficient (see default_damping()).

Reimplemented from Joint< T >.

◆ DoAddInOneForce()

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

Joint<T> override called through public NVI, Joint::AddInForce().

Therefore arguments were already checked to be valid. For a UniversalJoint, we must always have joint_dof < 2 since there are two degrees of freedom (num_velocities() == 2). joint_tau is the torque applied about the axis specified by joint_dof, the x-axis of the parent frame F if joint_dof = 0 or the y-axis of the child frame M if joint_dof = 1. The torque is applied to the body declared as child (according to the universal joint's constructor) at the origin of the child frame M (which is coincident with the origin of the parent frame F at all times). The torque is defined to be positive according to the right-hand-rule with the thumb aligned in the direction of the selected axis. That is, a positive torque causes a positive rotational acceleration (of the child body frame).

Implements Joint< T >.

◆ get_angles()

Vector2<T> get_angles ( const Context< T > &  context) const

Gets the rotation angles of this joint from context.

See class documentation for the definition of these angles.

Parameters
[in]contextThe context of the model this joint belongs to.
Returns
The angle coordinates of this joint stored in the context ordered as (θ₁, θ₂).

◆ get_angular_rates()

Vector2<T> get_angular_rates ( const systems::Context< T > &  context) const

Gets the rates of change, in radians per second, of this joint's angles (see class documentation) from context.

Parameters
[in]contextThe context of the model this joint belongs to.
Returns
The rates of change of this joint's angles as stored in the context.

◆ get_default_angles()

Vector2<double> get_default_angles ( ) const

Gets the default angles for this joint.

Wrapper for the more general Joint::default_positions().

Returns
The default angles of this stored in default_positions_

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ set_angles()

const UniversalJoint<T>& set_angles ( Context< T > *  context,
const Vector2< T > &  angles 
) const

Sets the context so that the generalized coordinates corresponding to the rotation angles of this joint equals angles.

Parameters
[in]contextThe context of the model this joint belongs to.
[in]anglesThe desired angles in radians to be stored in context ordered as (θ₁, θ₂). See class documentation for details.
Returns
a constant reference to this joint.

◆ set_angular_rates()

const UniversalJoint<T>& set_angular_rates ( systems::Context< T > *  context,
const Vector2< T > &  theta_dot 
) const

Sets the rates of change, in radians per second, of this this joint's angles (see class documentation) to theta_dot.

The new rates of change get stored in context.

Parameters
[in]contextThe context of the model this joint belongs to.
[in]theta_dotThe desired rates of change of this joints's angles in radians per second.
Returns
a constant reference to this joint.

◆ set_default_angles()

void set_default_angles ( const Vector2< double > &  angles)

Sets the default angles of this joint.

Parameters
[in]anglesThe desired default angles of the joint

◆ set_random_angles_distribution()

void set_random_angles_distribution ( const Vector2< symbolic::Expression > &  angles)

Sets the random distribution that angles of this joint will be randomly sampled from.

See class documentation for details on the definition of the angles.

◆ type_name()

const std::string& type_name ( ) const
overridevirtual

Returns a string identifying the type of this joint, such as "revolute" or "prismatic".

Implements Joint< T >.

Friends And Related Function Documentation

◆ UniversalJoint

friend class UniversalJoint
friend

Member Data Documentation

◆ kTypeName

const char kTypeName = "universal"
static

The name for this Joint type. It resolves to "universal".


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