Drake
PrismaticJoint< T > Class Template Referencefinal

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

#include <drake/multibody/multibody_tree/joints/prismatic_joint.h>

Inheritance diagram for PrismaticJoint< T >:
[legend]
Collaboration diagram for PrismaticJoint< T >:
[legend]

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 lower_limit=-std::numeric_limits< double >::infinity(), double 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...
 
const Vector3< double > & translation_axis () const
 Returns the axis of translation for this joint as a unit vector. More...
 
double damping () const
 Returns this joint's damping constant in N⋅s/m. More...
 
double lower_limit () const
 Returns the lower limit for this joint in meters. More...
 
double upper_limit () const
 Returns the upper limit for this joint in meters. More...
 
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

These methods require the provided context to be an instance of MultibodyTreeContext.

Failure to do so leads to a std::logic_error.

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...
 
- Public Member Functions inherited from Joint< T >
 Joint (const std::string &name, const Frame< T > &frame_on_parent, const Frame< T > &frame_on_child)
 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 num_dofs () const
 Returns the number of degrees of freedom for 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...
 
 Joint (const Joint &)=delete
 
Jointoperator= (const Joint &)=delete
 
 Joint (Joint &&)=delete
 
Jointoperator= (Joint &&)=delete
 

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 >
void DoSetTopology (const MultibodyTreeTopology &)
 
const JointImplementationget_implementation () const
 Returns a const reference to the internal implementation of this joint. More...
 

Friends

template<typename >
class PrismaticJoint
 
class JointTester
 

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. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T's are provided:

  • double
  • AutoDiffXd

They are already available to link against in the containing library. No other values for T are currently supported.

Member Typedef Documentation

using Context = systems::Context<Scalar>

Constructor & Destructor Documentation

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

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]lower_limitLower limit, in meters, for the translation coordinate (see get_translation()).
[in]upper_limitUpper 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 lower_limit > upper_limit.

Here is the call graph for this function:

Member Function Documentation

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

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.

Here is the call graph for this function:

Here is the caller graph for this function:

double damping ( ) const
inline

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

Here is the caller graph for this function:

void DoAddInDamping ( const systems::Context< T > &  context,
MultibodyForces< T > *  forces 
) const
inlineoverrideprotectedvirtual

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 damping()).

Reimplemented from Joint< T >.

Here is the call graph for this function:

void DoAddInOneForce ( const systems::Context< T > &  ,
int  joint_dof,
const T &  joint_tau,
MultibodyForces< T > *  forces 
) const
inlinefinalprotectedvirtual

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 (get_num_dofs() == 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 >.

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

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.

Here is the caller graph for this function:

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

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.

Here is the caller graph for this function:

double lower_limit ( ) const
inline

Returns the lower limit for this joint in meters.

Here is the caller graph for this function:

PrismaticJoint& operator= ( PrismaticJoint< T > &&  )
delete
PrismaticJoint& operator= ( const PrismaticJoint< T > &  )
delete
const PrismaticJoint<T>& set_translation ( Context< T > *  context,
const T &  translation 
) const
inline

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.
const PrismaticJoint<T>& set_translation_rate ( Context< T > *  context,
const T &  translation_dot 
) const
inline

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.
const Vector3<double>& translation_axis ( ) const
inline

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 frames's definitions) then, axis = axis_F = axis_M.

Here is the caller graph for this function:

double upper_limit ( ) const
inline

Returns the upper limit for this joint in meters.

Here is the caller graph for this function:

Friends And Related Function Documentation

friend class JointTester
friend
friend class PrismaticJoint
friend

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