Drake
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_P, const Frame< T > &frame_on_child_C, const math::RigidTransform< double > &X_PC)
 Constructor for a WeldJoint between a frame_on_parent_P and a frame_on_child_C so that their relative pose X_PC is fixed as if they were "welded" together. More...
 
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_PC () const
 Returns the pose X_PC of frame C in P. 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, const VectorX< double > &pos_lower_limits, const VectorX< double > &pos_upper_limits, const VectorX< double > &vel_lower_limits, const VectorX< double > &vel_upper_limits, const VectorX< double > &acc_lower_limits, const VectorX< double > &acc_upper_limits)
 Creates a joint between two Frame objects which imposes a given kinematic relation between frame F attached on the parent body P and frame M attached on the child body B. More...
 
virtual ~Joint ()
 
const std::string & name () const
 Returns the name of this joint. More...
 
const Body< T > & parent_body () const
 Returns a const reference to the parent body P. More...
 
const Body< T > & child_body () const
 Returns a const reference to the child body B. More...
 
const Frame< T > & frame_on_parent () const
 Returns a const reference to the frame F attached on the parent body P. More...
 
const Frame< T > & frame_on_child () const
 Returns a const reference to the frame M attached on the child body B. More...
 
int velocity_start () const
 Returns the index to the first generalized velocity for this joint within the vector v of generalized velocities for the full multibody system. More...
 
int num_velocities () const
 Returns the number of generalized velocities describing this joint. More...
 
int position_start () const
 Returns the index to the first generalized position for this joint within the vector q of generalized positions for the full multibody system. More...
 
int num_positions () const
 Returns the number of generalized positions describing this joint. More...
 
const T & GetOnePosition (const systems::Context< T > &context) const
 Returns the position coordinate for joints with a single degree of freedom. More...
 
const T & GetOneVelocity (const systems::Context< T > &context) const
 Returns the velocity coordinate for joints with a single degree of freedom. More...
 
void AddInOneForce (const systems::Context< T > &context, int joint_dof, const T &joint_tau, MultibodyForces< T > *forces) const
 Adds into forces a force along the one of the joint's degrees of freedom indicated by index joint_dof. More...
 
void AddInDamping (const systems::Context< T > &context, MultibodyForces< T > *forces) const
 Adds into forces the force due to damping within this joint. More...
 
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
 
 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...
 
- Public Member Functions inherited from MultibodyElement< Joint, T, JointIndex >
virtual ~MultibodyElement ()
 
JointIndex index () const
 Returns this element's unique index. More...
 
ModelInstanceIndex model_instance () const
 Returns the ModelInstanceIndex of the model instance to which this element belongs. More...
 
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...
 
 MultibodyElement (const MultibodyElement &)=delete
 
 MultibodyElement (MultibodyElement &&)=delete
 
MultibodyElementoperator= (const 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 const T & DoGetOnePosition (const systems::Context< T > &) const
 Implementation to the NVI GetOnePosition() that must only be implemented by those joint subclasses that have a single degree of freedom. More...
 
virtual const T & DoGetOneVelocity (const systems::Context< T > &) const
 Implementation to the NVI GetOneVelocity() that must only be implemented by those joint subclasses that have a single degree of freedom. More...
 
virtual void 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...
 
void DoDeclareParameters (internal::MultibodyTreeSystem< T > *tree_system) override
 Implementation of the NVI DeclareParameters(). More...
 
- Protected Member Functions inherited from MultibodyElement< Joint, T, JointIndex >
 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...
 
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_P,
const Frame< T > &  frame_on_child_C,
const math::RigidTransform< double > &  X_PC 
)

Constructor for a WeldJoint between a frame_on_parent_P and a frame_on_child_C so that their relative pose X_PC is fixed as if they were "welded" together.

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 P and C 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_PC()

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

Returns the pose X_PC of frame C in P.

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: