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
-
|
| | 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.
|
| | ~UniversalJoint () final |
| const std::string & | type_name () const final |
| | Returns a string identifying the type of this joint, such as "revolute" or "prismatic".
|
| double | default_damping () const |
| | Returns this joint's default damping constant in N⋅m⋅s.
|
| Vector2< double > | get_default_angles () const |
| | Gets the default angles for this joint.
|
| void | set_default_angles (const Vector2< double > &angles) |
| | Sets the default angles of this joint.
|
| void | set_random_angles_distribution (const Vector2< symbolic::Expression > &angles) |
| | Sets the random distribution that angles of this joint will be randomly sampled from.
|
| | UniversalJoint (const UniversalJoint &)=delete |
| UniversalJoint & | operator= (const UniversalJoint &)=delete |
| | UniversalJoint (UniversalJoint &&)=delete |
| UniversalJoint & | operator= (UniversalJoint &&)=delete |
| Vector2< T > | get_angles (const Context< T > &context) const |
| | Gets the rotation angles of this joint from context.
|
| 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.
|
| 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.
|
| 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.
|
| 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.
|
| | 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.
|
| virtual | ~Joint () |
| JointIndex | index () const |
| | Returns this element's unique index.
|
| JointOrdinal | ordinal () const |
| | Returns this element's unique ordinal.
|
| const std::string & | name () const |
| | Returns the name of this joint.
|
| const RigidBody< T > & | parent_body () const |
| | Returns a const reference to the parent body P.
|
| const RigidBody< T > & | child_body () const |
| | Returns a const reference to 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.
|
| const Frame< T > & | frame_on_child () const |
| | Returns a const reference to the frame M attached on the child body B.
|
| 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.
|
| int | num_velocities () const |
| | Returns the number of generalized velocities describing this joint.
|
| 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.
|
| int | num_positions () const |
| | Returns the number of generalized positions describing this joint.
|
| 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.
|
| std::string | position_suffix (int position_index_in_joint) const |
| | Returns a string suffix (e.g.
|
| std::string | velocity_suffix (int velocity_index_in_joint) const |
| | Returns a string suffix (e.g.
|
| const T & | GetOnePosition (const systems::Context< T > &context) const |
| | Returns the position coordinate for joints with 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.
|
| 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.
|
| void | AddInDamping (const systems::Context< T > &context, MultibodyForces< T > *forces) const |
| | Adds into forces the force due to damping within this joint.
|
| void | Lock (systems::Context< T > *context) const |
| | Lock the joint.
|
| void | Unlock (systems::Context< T > *context) const |
| | Unlock the joint.
|
| 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().
|
| const VectorX< T > & | GetDampingVector (const systems::Context< T > &context) const |
| | Returns the Context dependent damping coefficients stored as parameters in context.
|
| void | set_default_damping_vector (const VectorX< double > &damping) |
| | Sets the default value of the viscous damping coefficients for this joint.
|
| 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.
|
| | Joint (const Joint &)=delete |
| Joint & | operator= (const Joint &)=delete |
| | Joint (Joint &&)=delete |
| Joint & | operator= (Joint &&)=delete |
| const VectorX< double > & | position_lower_limits () const |
| | Returns the position lower limits.
|
| const VectorX< double > & | position_upper_limits () const |
| | Returns the position upper limits.
|
| const VectorX< double > & | velocity_lower_limits () const |
| | Returns the velocity lower limits.
|
| const VectorX< double > & | velocity_upper_limits () const |
| | Returns the velocity upper limits.
|
| const VectorX< double > & | acceleration_lower_limits () const |
| | Returns the acceleration lower limits.
|
| const VectorX< double > & | acceleration_upper_limits () const |
| | Returns the acceleration upper limits.
|
| void | set_position_limits (const VectorX< double > &lower_limits, const VectorX< double > &upper_limits) |
| | Sets the position limits to lower_limits and upper_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.
|
| void | set_acceleration_limits (const VectorX< double > &lower_limits, const VectorX< double > &upper_limits) |
| | Sets the acceleration limits to lower_limits and upper_limits.
|
| void | set_default_positions (const VectorX< double > &default_positions) |
| | Sets the default generalized position coordinates q₀ to default_positions.
|
| const VectorX< double > & | default_positions () const |
| | Returns the default generalized position coordinates q₀.
|
| 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.
|
| 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.
|
| 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.
|
| 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.
|
| 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.
|
| math::RigidTransform< double > | GetDefaultPose () const |
| | Returns this joint's default pose as a RigidTransform X_FM.
|
| 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.
|
| 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).
|
| 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.
|
| 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.
|
| 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.
|
| 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.
|
| 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.
|
| 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.
|
| 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.
|
| template<typename = void> |
| const MultibodyPlant< T > & | GetParentPlant () const |
| | Returns the MultibodyPlant that owns this MultibodyElement.
|
| void | DeclareParameters (internal::MultibodyTreeSystem< T > *tree_system) |
| | Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time.
|
| void | SetDefaultParameters (systems::Parameters< T > *parameters) const |
| | Sets default values of parameters belonging to each MultibodyElement in parameters at a call to MultibodyTreeSystem::SetDefaultParameters().
|
| void | DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system) |
| | Declares MultibodyTreeSystem discrete states.
|
| void | DeclareCacheEntries (internal::MultibodyTreeSystem< T > *tree_system) |
| | (Advanced) Declares all cache entries needed by this element.
|
| bool | is_ephemeral () const |
| | Returns true if this MultibodyElement was added during Finalize() rather than something a user added.
|
| void | set_is_ephemeral (bool is_ephemeral) |
| | (Internal use only) Sets the is_ephemeral flag to the indicated value.
|
| | MultibodyElement (const MultibodyElement &)=delete |
| MultibodyElement & | operator= (const MultibodyElement &)=delete |
| | MultibodyElement (MultibodyElement &&)=delete |
| MultibodyElement & | operator= (MultibodyElement &&)=delete |
|
| void | DoAddInOneForce (const systems::Context< T > &, int joint_dof, const T &joint_tau, MultibodyForces< T > *forces) const final |
| | Joint<T> override called through public NVI, Joint::AddInForce().
|
| void | DoAddInDamping (const systems::Context< T > &context, MultibodyForces< T > *forces) const final |
| | Joint<T> override called through public NVI, Joint::AddInDamping().
|
| 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().
|
| virtual std::pair< Eigen::Quaternion< double >, Vector3< double > > | DoGetDefaultPosePair () const |
| | Implementation of the NVI GetDefaultPose().
|
| 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.
|
| 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.
|
| void | DoSetTopology () override |
| | Implementation of the NVI SetTopology().
|
| 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.
|
| 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.
|
| template<template< typename > class ConcreteMobilizer> |
| ConcreteMobilizer< T > & | get_mutable_mobilizer_downcast () |
| | (Internal use only) Mutable flavor of get_mobilizer_downcast().
|
| bool | has_mobilizer () const |
| | (Internal use only) Returns true if this Joint has an implementing Mobilizer.
|
| 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.
|
| | MultibodyElement (ModelInstanceIndex model_instance) |
| | Constructor which allows specifying a model instance.
|
| | MultibodyElement (ModelInstanceIndex model_instance, int64_t index) |
| | Both the model instance and element index are specified.
|
| template<typename ElementIndexType> |
| ElementIndexType | index_impl () const |
| | Returns this element's unique index.
|
| template<typename ElementOrdinalType = int64_t> |
| ElementOrdinalType | ordinal_impl () const |
| | Returns this element's unique ordinal.
|
| const internal::MultibodyTree< T > & | get_parent_tree () const |
| | Returns a constant reference to the parent MultibodyTree that owns this element.
|
| const internal::MultibodyTreeSystem< T > & | GetParentTreeSystem () const |
| | Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element.
|
| void | SetTopology () |
| | (Internal use only) Gives MultibodyElement-derived objects the opportunity to set data members that depend on topology and coordinate assignments having been finalized.
|
| virtual void | DoDeclareDiscreteState (internal::MultibodyTreeSystem< T > *) |
| | Implementation of the NVI DeclareDiscreteState().
|
| virtual void | DoDeclareCacheEntries (internal::MultibodyTreeSystem< T > *) |
| | Derived classes must override this method to declare cache entries needed by this element.
|
| 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().
|
| 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().
|
| systems::DiscreteStateIndex | DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system, const VectorX< T > &model_value) |
| | To be used by MultibodyElement-derived objects when declaring discrete states in their implementation of DoDeclareDiscreteStates().
|
| systems::CacheEntry & | DeclareCacheEntry (internal::MultibodyTreeSystem< T > *tree_system, std::string description, systems::ValueProducer value_producer, std::set< systems::DependencyTicket > prerequisites_of_calc) |
| | To be used by MultibodyElement-derived objects when declaring cache entries in their implementation of DoDeclareCacheEntries().
|
| bool | has_parent_tree () const |
| | Returns true if this multibody element has a parent tree, otherwise false.
|