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

Detailed Description

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

This Joint fixes the relative pose between two frames as if "welding" them together.

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

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

Public Types

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

Public Member Functions

 WeldJoint (const std::string &name, const Frame< T > &frame_on_parent_F, const Frame< T > &frame_on_child_M, const math::RigidTransform< double > &X_FM)
 Constructor for a WeldJoint between a frame_on_parent_F and a frame_on_child_M so that their relative pose X_FM is fixed as if they were "welded" together. More...
 
 ~WeldJoint () override
 
const std::string & type_name () const override
 Returns a string identifying the type of this joint, such as "revolute" or "prismatic". More...
 
const math::RigidTransform< double > & X_FM () const
 Returns the pose X_FM of frame M in F. More...
 
Does not allow copy, move, or assignment
 WeldJoint (const WeldJoint &)=delete
 
WeldJointoperator= (const WeldJoint &)=delete
 
 WeldJoint (WeldJoint &&)=delete
 
WeldJointoperator= (WeldJoint &&)=delete
 
- 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
 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...
 
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< doubleGetDefaultPose () 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 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 [] = "weld"
 

Protected Member Functions

void DoAddInOneForce (const systems::Context< T > &, int, const T &, MultibodyForces< T > *) const override
 Joint<T> override called through public NVI, Joint::AddInForce(). 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...
 
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...
 
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 WeldJoint
 

Member Typedef Documentation

◆ Context

using Context = systems::Context<Scalar>

Constructor & Destructor Documentation

◆ WeldJoint() [1/3]

WeldJoint ( const WeldJoint< T > &  )
delete

◆ WeldJoint() [2/3]

WeldJoint ( WeldJoint< T > &&  )
delete

◆ WeldJoint() [3/3]

WeldJoint ( const std::string &  name,
const Frame< T > &  frame_on_parent_F,
const Frame< T > &  frame_on_child_M,
const math::RigidTransform< double > &  X_FM 
)

Constructor for a WeldJoint between a frame_on_parent_F and a frame_on_child_M so that their relative pose X_FM is fixed as if they were "welded" together.

◆ ~WeldJoint()

~WeldJoint ( )
override

Member Function Documentation

◆ DoAddInOneForce()

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

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

Since frame F and M are welded together, it is physically not possible to apply forces between them. Therefore this method throws an exception if invoked.

Implements Joint< T >.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ 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 >.

◆ X_FM()

const math::RigidTransform<double>& X_FM ( ) const

Returns the pose X_FM of frame M in F.

Friends And Related Function Documentation

◆ WeldJoint

friend class WeldJoint
friend

Member Data Documentation

◆ kTypeName

const char kTypeName = "weld"
static

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