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

Detailed Description

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

This Joint allows two bodies to translate relative to one another along a common axis.

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 frames F and M to translate with respect to each other along an axis â. The translation distance is defined positive when child body B translates along the direction of â. Axis â is constant and has the same measures in both frames F and M, that is, â_F = â_M.

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

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

Public Types

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

Public Member Functions

 PrismaticJoint (const std::string &name, const Frame< T > &frame_on_parent, const Frame< T > &frame_on_child, const Vector3< double > &axis, double pos_lower_limit=-std::numeric_limits< double >::infinity(), double pos_upper_limit=std::numeric_limits< double >::infinity(), double damping=0)
 Constructor to create a prismatic joint between two bodies so that frame F attached to the parent body P and frame M attached to the child body B, translate relatively to one another along a common axis. More...
 
 ~PrismaticJoint () override
 
const std::string & type_name () const override
 Returns a string identifying the type of this joint, such as "revolute" or "prismatic". More...
 
const Vector3< double > & translation_axis () const
 Returns the axis of translation for this joint as a unit vector. More...
 
double default_damping () const
 Returns this joint's default damping constant in N⋅s/m. More...
 
void set_default_damping (double damping)
 Sets the default value of viscous damping for this joint, in N⋅s/m. More...
 
double position_lower_limit () const
 Returns the position lower limit for this joint in meters. More...
 
double position_upper_limit () const
 Returns the position upper limit for this joint in meters. More...
 
double velocity_lower_limit () const
 Returns the velocity lower limit for this joint in meters per second. More...
 
double velocity_upper_limit () const
 Returns the velocity upper limit for this joint in meters per second. More...
 
double acceleration_lower_limit () const
 Returns the acceleration lower limit for this joint in meters per second squared. More...
 
double acceleration_upper_limit () const
 Returns the acceleration upper limit for this joint in meters per second squared. More...
 
double get_default_translation () const
 Gets the default translation. More...
 
void set_default_translation (double translation)
 Sets the default_positions of this joint (in this case a single translation) More...
 
void set_random_translation_distribution (const symbolic::Expression &translation)
 
void AddInForce (const systems::Context< T > &context, const T &force, MultibodyForces< T > *multibody_forces) const
 Adds into multibody_forces a given force, in Newtons, for this joint that is to be applied along the joint's axis. More...
 
Does not allow copy, move, or assignment
 PrismaticJoint (const PrismaticJoint &)=delete
 
PrismaticJointoperator= (const PrismaticJoint &)=delete
 
 PrismaticJoint (PrismaticJoint &&)=delete
 
PrismaticJointoperator= (PrismaticJoint &&)=delete
 
Context-dependent value access
const T & get_translation (const Context< T > &context) const
 Gets the translation distance of this mobilizer from context. More...
 
const PrismaticJoint< T > & set_translation (Context< T > *context, const T &translation) const
 Sets context so that the generalized coordinate corresponding to the translation distance of this joint equals translation. More...
 
const T & get_translation_rate (const Context< T > &context) const
 Gets the rate of change, in meters per second, of this joint's translation distance (see get_translation()) from context. More...
 
const PrismaticJoint< T > & set_translation_rate (Context< T > *context, const T &translation_dot) const
 Sets the rate of change, in meters per second, of this joint's translation distance to translation_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 const char kTypeName [] = "prismatic"
 

Protected Member Functions

void DoAddInOneForce (const systems::Context< T > &, int joint_dof, const T &joint_tau, MultibodyForces< T > *forces) const final
 Joint<T> virtual 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...
 
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 PrismaticJoint
 

Member Typedef Documentation

◆ Context

using Context = systems::Context<Scalar>

Constructor & Destructor Documentation

◆ PrismaticJoint() [1/3]

PrismaticJoint ( const PrismaticJoint< T > &  )
delete

◆ PrismaticJoint() [2/3]

PrismaticJoint ( PrismaticJoint< T > &&  )
delete

◆ PrismaticJoint() [3/3]

PrismaticJoint ( const std::string &  name,
const Frame< T > &  frame_on_parent,
const Frame< T > &  frame_on_child,
const Vector3< double > &  axis,
double  pos_lower_limit = -std::numeric_limits< double >::infinity(),
double  pos_upper_limit = std::numeric_limits< double >::infinity(),
double  damping = 0 
)

Constructor to create a prismatic joint between two bodies so that frame F attached to the parent body P and frame M attached to the child body B, translate relatively to one another along a common axis.

See this class's documentation for further details on the definition of these frames and translation distance. The first three arguments to this constructor are those of the Joint class constructor. See the Joint class's documentation for details. The additional parameter axis is:

Parameters
[in]axisA vector in ℝ³ specifying the translation axis for this joint. Given that frame M only translates with respect to F and there is no relative rotation, the measures of axis in either frame F or M are exactly the same, that is, axis_F = axis_M. This vector can have any length, only the direction is used.
[in]pos_lower_limitLower position limit, in meters, for the translation coordinate (see get_translation()).
[in]pos_upper_limitUpper position limit, in meters, for the translation coordinate (see get_translation()).
[in]dampingViscous damping coefficient, in N⋅s/m, used to model losses within the joint. The damping force (in N) is modeled as f = -damping⋅v, i.e. opposing motion, with v the translational speed for this joint (see get_translation_rate()).
Exceptions
std::exceptionif the L2 norm of axis is less than the square root of machine epsilon.
std::exceptionif damping is negative.
std::exceptionif pos_lower_limit > pos_upper_limit.

◆ ~PrismaticJoint()

~PrismaticJoint ( )
override

Member Function Documentation

◆ acceleration_lower_limit()

double acceleration_lower_limit ( ) const

Returns the acceleration lower limit for this joint in meters per second squared.

◆ acceleration_upper_limit()

double acceleration_upper_limit ( ) const

Returns the acceleration upper limit for this joint in meters per second squared.

◆ AddInForce()

void AddInForce ( const systems::Context< T > &  context,
const T &  force,
MultibodyForces< T > *  multibody_forces 
) const

Adds into multibody_forces a given force, in Newtons, for this joint that is to be applied along the joint's axis.

The force is defined to be positive in the direction along this joint's axis. That is, a positive force causes a positive translational acceleration along the joint's axis.

◆ default_damping()

double default_damping ( ) const

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

◆ 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 force according to the viscous law f = -d⋅v, 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
finalprotectedvirtual

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

Therefore arguments were already checked to be valid. For a PrismaticJoint, we must always have joint_dof = 0 since there is only a single degree of freedom (num_velocities() == 1). joint_tau is the linear force applied along the joint's axis, on the body declared as child (according to the prismatic joint's constructor) at the origin of the child frame (which is coincident with the origin of the parent frame at all times).

Implements Joint< T >.

◆ get_default_translation()

double get_default_translation ( ) const

Gets the default translation.

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

Returns
The default translation of this stored in default_positions_.

◆ get_translation()

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

Gets the translation distance of this mobilizer from context.

Parameters
[in]contextThe context of the MultibodyTree this joint belongs to.
Returns
The translation coordinate of this joint read from context.

◆ get_translation_rate()

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

Gets the rate of change, in meters per second, of this joint's translation distance (see get_translation()) from context.

Parameters
[in]contextThe context of the MultibodyTree this joint belongs to.
Returns
The rate of change of this joint's translation read from 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]

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

◆ operator=() [2/2]

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

◆ position_lower_limit()

double position_lower_limit ( ) const

Returns the position lower limit for this joint in meters.

◆ position_upper_limit()

double position_upper_limit ( ) const

Returns the position upper limit for this joint in meters.

◆ set_default_damping()

void set_default_damping ( double  damping)

Sets the default value of viscous damping for this joint, in N⋅s/m.

Exceptions
std::exceptionif damping is negative.
Precondition
the MultibodyPlant must not be finalized.

◆ set_default_translation()

void set_default_translation ( double  translation)

Sets the default_positions of this joint (in this case a single translation)

Parameters
[in]translationThe desired default translation of the joint

◆ set_random_translation_distribution()

void set_random_translation_distribution ( const symbolic::Expression translation)

◆ set_translation()

const PrismaticJoint<T>& set_translation ( Context< T > *  context,
const T &  translation 
) const

Sets context so that the generalized coordinate corresponding to the translation distance of this joint equals translation.

Parameters
[in]contextThe context of the MultibodyTree this joint belongs to.
[in]translationThe desired translation in meters to be stored in context.
Returns
a constant reference to this joint.

◆ set_translation_rate()

const PrismaticJoint<T>& set_translation_rate ( Context< T > *  context,
const T &  translation_dot 
) const

Sets the rate of change, in meters per second, of this joint's translation distance to translation_dot.

The new rate of change translation_dot gets stored in context.

Parameters
[in]contextThe context of the MultibodyTree this joint belongs to.
[in]translation_dotThe desired rate of change of this joints's translation in meters per second.
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.

◆ translation_axis()

const Vector3<double>& translation_axis ( ) const

Returns the axis of translation for 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.

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

◆ velocity_lower_limit()

double velocity_lower_limit ( ) const

Returns the velocity lower limit for this joint in meters per second.

◆ velocity_upper_limit()

double velocity_upper_limit ( ) const

Returns the velocity upper limit for this joint in meters per second.

Friends And Related Function Documentation

◆ PrismaticJoint

friend class PrismaticJoint
friend

Member Data Documentation

◆ kTypeName

const char kTypeName = "prismatic"
static

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