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

Detailed Description

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

This Joint allows two bodies to rotate freely relative to one another.

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 rotate freely with respect to F, while the origins, Mo and Fo, of frames M and F respectively remain coincident. The orientation of M relative to F is parameterized with space x-y-z Euler angles.

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

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

Public Types

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

Public Member Functions

 BallRpyJoint (const std::string &name, const Frame< T > &frame_on_parent, const Frame< T > &frame_on_child, double damping=0)
 Constructor to create a ball rpy joint between two bodies so that frame F attached to the parent body P and frame M attached to the child body B rotate freely relative to one another. More...
 
const std::string & type_name () const override
 Returns a string identifying the type of this joint, such as "revolute" or "prismatic". More...
 
double default_damping () const
 Returns this joint's default damping constant in N⋅m⋅s. More...
 
double damping () const
 (Deprecated.) More...
 
Vector3< doubleget_default_angles () const
 Gets the default angles for this joint. More...
 
void set_default_angles (const Vector3< double > &angles)
 Sets the default angles of this joint. More...
 
Does not allow copy, move, or assignment
 BallRpyJoint (const BallRpyJoint &)=delete
 
BallRpyJointoperator= (const BallRpyJoint &)=delete
 
 BallRpyJoint (BallRpyJoint &&)=delete
 
BallRpyJointoperator= (BallRpyJoint &&)=delete
 
Context-dependent value access
Vector3< T > get_angles (const Context< T > &context) const
 Gets the rotation angles of this joint from context. More...
 
const BallRpyJoint< T > & set_angles (Context< T > *context, const Vector3< T > &angles) const
 Sets the context so that the generalized coordinates corresponding to the rotation angles of this joint equals angles. More...
 
void set_random_angles_distribution (const Vector3< symbolic::Expression > &angles)
 Sets the random distribution that angles of this joint will be randomly sampled from. More...
 
Vector3< T > get_angular_velocity (const systems::Context< T > &context) const
 Retrieves from context the angular velocity w_FM of the child frame M in the parent frame F, expressed in F. More...
 
const BallRpyJoint< T > & set_angular_velocity (systems::Context< T > *context, const Vector3< T > &w_FM) const
 Sets in context the state for this joint so that the angular velocity of the child frame M in the parent frame F is w_FM. 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...
 
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< double > & damping_vector () const
 (Deprecated.) 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 [] = "ball_rpy"
 The name for this Joint type. It resolves to "ball_rpy". More...
 

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

Member Typedef Documentation

◆ Context

using Context = systems::Context<Scalar>

Constructor & Destructor Documentation

◆ BallRpyJoint() [1/3]

BallRpyJoint ( const BallRpyJoint< T > &  )
delete

◆ BallRpyJoint() [2/3]

BallRpyJoint ( BallRpyJoint< T > &&  )
delete

◆ BallRpyJoint() [3/3]

BallRpyJoint ( const std::string &  name,
const Frame< T > &  frame_on_parent,
const Frame< T > &  frame_on_child,
double  damping = 0 
)

Constructor to create a ball rpy joint between two bodies so that frame F attached to the parent body P and frame M attached to the child body B rotate freely relative to one another.

See this class's documentation for further details on the definition of these frames, get_angles() for an explanation of the angles defining orientation, and get_angular_velocity() for an explanation of the generalized velocities. This constructor signature creates a joint with no joint limits, i.e. the joint position, velocity and acceleration limits are the pair (-∞, ∞). These can be set using the Joint methods set_position_limits(), set_velocity_limits() and set_acceleration_limits(). 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]dampingViscous damping coefficient, in N⋅m⋅s, 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.

Member Function Documentation

◆ damping()

double damping ( ) const

(Deprecated.)

Deprecated:
Use default_damping() instead.
This will be removed from Drake on or after 2024-06-01.

◆ default_damping()

double default_damping ( ) const

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

The damping torque (in N⋅m) is modeled as τ = -damping⋅ω, i.e. opposing motion, with ω the angular velocity of frame M in F (see get_angular_velocity()) and τ the torque on child body B (to which M is rigidly attached).

◆ 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 torque according to the viscous law τ = -d⋅ω, with d the damping coefficient (see default_damping()).

Reimplemented from Joint< T >.

◆ DoAddInOneForce()

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

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

Adding forces per-dof makes no physical sense. Therefore, this method throws an exception if invoked.

Implements Joint< T >.

◆ get_angles()

Vector3<T> get_angles ( const Context< T > &  context) const

Gets the rotation angles of this joint from context.

The orientation R_FM of the child frame M in parent frame F is parameterized with space x-y-z Euler angles (also known as extrinsic angles). That is, the angles θr, θp, θy, correspond to a sequence of rotations about the x̂, ŷ, ẑ axes of parent frame F, respectively. Mathematically, rotation R_FM is given in terms of angles θr, θp, θy by:

  R_FM(q) = Rz(θy) * Ry(θp) * Rx(θr)

where Rx(θ), Ry(θ) and Rz(θ) correspond to the elemental rotations in amount of θ about the x, y and z axes respectively. Zero θr, θp, θy angles corresponds to frames F and M being coincident. Angles θr, θp, θy are defined to be positive according to the right-hand-rule with the thumb aligned in the direction of their respective axes.

Note
Space x-y-z angles (extrinsic) are equivalent to Body z-y-x angles (intrinsic).
This particular choice of angles θr, θp, θy for this joint are many times referred to as the roll, pitch and yaw angles by many dynamicists. They are also known as the Tait-Bryan angles or Cardan angles.
Parameters
[in]contextThe context of the model this joint belongs to.
Returns
The angle coordinates of this joint stored in the context ordered as θr, θp, θy.

◆ get_angular_velocity()

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

Retrieves from context the angular velocity w_FM of the child frame M in the parent frame F, expressed in F.

Parameters
[in]contextThe context of the model this joint belongs to.
Return values
w_FMA vector in ℝ³ with the angular velocity of the child frame M in the parent frame F, expressed in F. Refer to this class's documentation for further details and definitions of these frames.

◆ get_default_angles()

Vector3<double> get_default_angles ( ) const

Gets the default angles for this joint.

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

Returns
The default angles of this stored in default_positions_

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ set_angles()

const BallRpyJoint<T>& set_angles ( Context< T > *  context,
const Vector3< T > &  angles 
) const

Sets the context so that the generalized coordinates corresponding to the rotation angles of this joint equals angles.

Parameters
[in]contextThe context of the model this joint belongs to.
[in]anglesThe desired angles in radians to be stored in context ordered as θr, θp, θy. See get_angles() for details.
Returns
a constant reference to this joint.

◆ set_angular_velocity()

const BallRpyJoint<T>& set_angular_velocity ( systems::Context< T > *  context,
const Vector3< T > &  w_FM 
) const

Sets in context the state for this joint so that the angular velocity of the child frame M in the parent frame F is w_FM.

Parameters
[out]contextThe context of the model this joint belongs to.
[in]w_FMA vector in ℝ³ with the angular velocity of the child frame M in the parent frame F, expressed in F. Refer to this class's documentation for further details and definitions of these frames.
Returns
a constant reference to this joint.

◆ set_default_angles()

void set_default_angles ( const Vector3< double > &  angles)

Sets the default angles of this joint.

Parameters
[in]anglesThe desired default angles of the joint

◆ set_random_angles_distribution()

void set_random_angles_distribution ( const Vector3< symbolic::Expression > &  angles)

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

See get_angles() for details on the angle representation.

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

Friends And Related Function Documentation

◆ BallRpyJoint

friend class BallRpyJoint
friend

Member Data Documentation

◆ kTypeName

const char kTypeName = "ball_rpy"
static

The name for this Joint type. It resolves to "ball_rpy".


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