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

Detailed Description

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

This joint models a screw joint allowing two bodies to rotate about one axis while translating along that same axis with one degree of freedom.

That is, 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), this joint allows frame M to translate (while rotating) along an axis â. Axis â is constant and has the same measures in both frames F and M, that is, â_F = â_M. The rotation about the â_F axis and its rate specify the state of the joint. Zero (θ) corresponds to frames F and M being coincident and aligned. The translation distance is defined positive when child body B translates along the direction of â, and the rotation θ is defined to be positive according to the right-hand-rule with the thumb aligned in the direction of the â_F axis.

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

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

Public Types

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

Public Member Functions

 ScrewJoint (const std::string &name, const Frame< T > &frame_on_parent, const Frame< T > &frame_on_child, double screw_pitch, double damping)
 Constructor to create a screw joint between two bodies so that frame F attached to the parent body P and frame M attached to the child body B translate and rotate as described in the class's documentation. More...
 
 ScrewJoint (const std::string &name, const Frame< T > &frame_on_parent, const Frame< T > &frame_on_child, const Vector3< double > &axis, double screw_pitch, double damping)
 Constructor to create a screw joint between two bodies so that frame F attached to the parent body P and frame M attached to the child body B translate and rotate as described in the class's documentation. More...
 
 ~ScrewJoint () final
 
const std::string & type_name () const final
 Returns a string identifying the type of this joint, such as "revolute" or "prismatic". More...
 
const Vector3< double > & screw_axis () const
 Returns the normalized axis of motion of this joint as a unit vector. More...
 
double screw_pitch () const
 Returns this joint's amount of translation in meters occurring over a one full revolution. More...
 
double default_damping () const
 Returns this joint's default damping constant N⋅m⋅s for the rotational degree. More...
 
double get_default_translation () const
 Gets the default position for this joint. More...
 
void set_default_translation (const double &z)
 Sets the default translation of this joint. More...
 
double get_default_rotation () const
 Gets the default angle for this joint. More...
 
void set_default_rotation (double theta)
 Sets the default angle of this joint. More...
 
void set_random_pose_distribution (const Vector1< symbolic::Expression > &theta)
 Sets the random distribution that the angle of this joint will be randomly sampled from. More...
 
Does not allow copy, move, or assignment
 ScrewJoint (const ScrewJoint &)=delete
 
ScrewJointoperator= (const ScrewJoint &)=delete
 
 ScrewJoint (ScrewJoint &&)=delete
 
ScrewJointoperator= (ScrewJoint &&)=delete
 
Context-dependent value access
get_translation (const Context< T > &context) const
 Gets the translation of this joint from context. More...
 
const ScrewJoint< T > & set_translation (Context< T > *context, const T &z) const
 Sets the context so that the translation of this joint equals to (z). More...
 
const T & get_rotation (const systems::Context< T > &context) const
 Gets the angle θ of this joint from context. More...
 
const ScrewJoint< T > & set_rotation (systems::Context< T > *context, const T &theta) const
 Sets the context so that the angle θ of this joint equals theta. More...
 
get_translational_velocity (const systems::Context< T > &context) const
 Gets the translational velocity vz, in meters per second, of this joint's Mo measured and expressed in frame F from context. More...
 
const ScrewJoint< T > & set_translational_velocity (systems::Context< T > *context, const T &vz) const
 Sets the translational velocity, in meters per second, of this this joint's Mo along frame F's â-axis to vz. More...
 
const T & get_angular_velocity (const systems::Context< T > &context) const
 Gets the rate of change, in radians per second, of this joint's angle θ from context. More...
 
const ScrewJoint< T > & set_angular_velocity (systems::Context< T > *context, const T &theta_dot) const
 Sets the rate of change, in radians per second, of this joint's angle θ (see class documentation) to theta_dot. More...
 
const T & GetDamping (const Context< T > &context) const
 Returns the Context dependent damping coefficient stored as a parameter in context. More...
 
void SetDamping (Context< T > *context, const T &damping) const
 Sets the value of the viscous damping coefficient for this joint, stored as a parameter in context. 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 constexpr char kTypeName [] = "screw"
 The name for this Joint type. More...
 

Friends

template<typename >
class ScrewJoint
 

Additional Inherited Members

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

Member Typedef Documentation

◆ Context

using Context = systems::Context<Scalar>

Constructor & Destructor Documentation

◆ ScrewJoint() [1/4]

ScrewJoint ( const ScrewJoint< T > &  )
delete

◆ ScrewJoint() [2/4]

ScrewJoint ( ScrewJoint< T > &&  )
delete

◆ ScrewJoint() [3/4]

ScrewJoint ( const std::string &  name,
const Frame< T > &  frame_on_parent,
const Frame< T > &  frame_on_child,
double  screw_pitch,
double  damping 
)

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

This constructor signature creates a joint with the axis â set to the z-axis and no joint limits, i.e. the joint angular position, angular velocity and angular acceleration limits are the pair (-∞, ∞). These can be set using the Joint methods set_position_limits(), set_velocity_limits() and set_acceleration_limits() in radians, radians/s, radians/s² units. 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]screw_pitchAmount of translation in meters occurring over a one full screw revolution. It's domain is (-∞, ∞). When the screw pitch is negative, positive rotation will result in translating towards the negative direction of z-axis. When the screw pitch is zero, this joint will behave like a revolute joint.
[in]dampingViscous damping coefficient, N⋅m⋅s/rad for rotation, 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.

◆ ScrewJoint() [4/4]

ScrewJoint ( const std::string &  name,
const Frame< T > &  frame_on_parent,
const Frame< T > &  frame_on_child,
const Vector3< double > &  axis,
double  screw_pitch,
double  damping 
)

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

This constructor signature creates a joint with no joint limits, i.e. the joint angular position, angular velocity and angular acceleration limits are the pair (-∞, ∞). These can be set using the Joint methods set_position_limits(), set_velocity_limits() and set_acceleration_limits() in radians, radians/s, radians/s² units. 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]axisA vector in ℝ³ specifying the axis of motion for this joint. The coordinates of axis expressed in frames F and M are the same at all times, that is, axis_F = axis_M. In other words, axis_F (or axis_M) is the eigenvector of R_FM with eigenvalue equal to one. This vector can have any length, only the direction is used.
[in]screw_pitchAmount of translation in meters occurring over a one full screw revolution. It's domain is (-∞, ∞). When the screw pitch is negative, positive rotation will result in translating towards the negative direction of â-axis. When the screw pitch is zero, this joint will behave like a revolute joint.
[in]dampingViscous damping coefficient, N⋅m⋅s/rad for rotation, used to model losses within the joint. See documentation of default_damping() for details on modelling of the damping torque.
Exceptions
std::exceptionif the L2 norm of axis is less than the square root of machine epsilon.
std::exceptionif damping is negative.

◆ ~ScrewJoint()

~ScrewJoint ( )
final

Member Function Documentation

◆ default_damping()

double default_damping ( ) const

Returns this joint's default damping constant N⋅m⋅s for the rotational degree.

The damping torque (in N⋅m) is modeled as τ = -damping⋅ω i.e. opposing motion, with ω the angular rate for this joint (see get_angular_velocity()) and τ the torque on child body B expressed in frame F as t_B_F = τ⋅Fâ_F.

◆ get_angular_velocity()

const T& get_angular_velocity ( const systems::Context< T > &  context) const

Gets the rate of change, in radians per second, of this joint's angle θ from context.

See class documentation for the definition of this angle.

Parameters
[in]contextThe context of the model this joint belongs to.
Return values
theta_dotThe rate of change of this joint's angle θ as stored in the context.

◆ get_default_rotation()

double get_default_rotation ( ) const

Gets the default angle for this joint.

Return values
thetaThe default angle of this joint.

◆ get_default_translation()

double get_default_translation ( ) const

Gets the default position for this joint.

Return values
zThe default position of this joint.

◆ get_rotation()

const T& get_rotation ( const systems::Context< T > &  context) const

Gets the angle θ of this joint from context.

Parameters
[in]contextThe context of the model this joint belongs to.
Return values
thetaThe angle of this joint stored in the context. See class documentation for details.

◆ get_translation()

T get_translation ( const Context< T > &  context) const

Gets the translation of this joint from context.

Parameters
[in]contextThe context of the model this joint belongs to.
Return values
zThe translation of this joint stored in the context as (z). See class documentation for details.

◆ get_translational_velocity()

T get_translational_velocity ( const systems::Context< T > &  context) const

Gets the translational velocity vz, in meters per second, of this joint's Mo measured and expressed in frame F from context.

Parameters
[in]contextThe context of the model this joint belongs to.
Return values
vzThe translational velocity of this joint as stored in the context.

◆ GetDamping()

const T& GetDamping ( const Context< T > &  context) const

Returns the Context dependent damping coefficient stored as a parameter in context.

Refer to default_damping() for details.

Parameters
[in]contextThe context storing the state and parameters for the model to which this joint belongs.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ screw_axis()

const Vector3<double>& screw_axis ( ) const

Returns the normalized axis of motion of this joint as a unit vector.

Since the measures of this axis in either frame F or M are the same (see this class's documentation for frame definitions) then, axis = axis_F = axis_M.

◆ screw_pitch()

double screw_pitch ( ) const

Returns this joint's amount of translation in meters occurring over a one full revolution.

◆ set_angular_velocity()

const ScrewJoint<T>& set_angular_velocity ( systems::Context< T > *  context,
const T &  theta_dot 
) const

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

The new rate of change gets stored in context.

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

◆ set_default_rotation()

void set_default_rotation ( double  theta)

Sets the default angle of this joint.

This will change the default_translation too, because they are not independent in this joint.

Parameters
[in]thetaThe desired default angle of the joint

◆ set_default_translation()

void set_default_translation ( const double z)

Sets the default translation of this joint.

This will change the default_rotation too, which are not independent in this joint.

Parameters
[in]zThe desired default translation of the joint
Exceptions
std::exceptionif pitch is very near zero.

◆ set_random_pose_distribution()

void set_random_pose_distribution ( const Vector1< symbolic::Expression > &  theta)

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

See class documentation for details on the definition of the position and angle.

◆ set_rotation()

const ScrewJoint<T>& set_rotation ( systems::Context< T > *  context,
const T &  theta 
) const

Sets the context so that the angle θ of this joint equals theta.

Parameters
[in]contextThe context of the model this joint belongs to.
[in]thetaThe desired angle in radians to be stored in context. See class documentation for details.
Returns
a constant reference to this joint.

◆ set_translation()

const ScrewJoint<T>& set_translation ( Context< T > *  context,
const T &  z 
) const

Sets the context so that the translation of this joint equals to (z).

Parameters
[in]contextThe context of the model this joint belongs to.
[in]zThe desired translation in meters to be stored in context as (z). See class documentation for details.
Returns
a constant reference to this joint.

◆ set_translational_velocity()

const ScrewJoint<T>& set_translational_velocity ( systems::Context< T > *  context,
const T &  vz 
) const

Sets the translational velocity, in meters per second, of this this joint's Mo along frame F's â-axis to vz.

The new translational velocity gets stored in context.

Parameters
[in]contextThe context of the model this joint belongs to.
[in]vzThe desired translational velocity of this joint in meters per second along F frame's â-axis.
Returns
a constant reference to this joint.

◆ SetDamping()

void SetDamping ( Context< T > *  context,
const T &  damping 
) const

Sets the value of the viscous damping coefficient for this joint, stored as a parameter in context.

Refer to default_damping() for details.

Parameters
[out]contextThe context storing the state and parameters for the model to which this joint belongs.
[in]dampingThe damping value.
Exceptions
std::exceptionif damping is negative.

◆ type_name()

const std::string& type_name ( ) const
finalvirtual

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

Implements Joint< T >.

Friends And Related Function Documentation

◆ ScrewJoint

friend class ScrewJoint
friend

Member Data Documentation

◆ kTypeName

constexpr char kTypeName[] = "screw"
static

The name for this Joint type.


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