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

Detailed Description

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

This Joint allows a rigid body to move freely with respect to its parent rigid body.

This is most commonly used to allow a body to move freely with respect to the World, but can be used with any parent. More precisely, 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 and rotate freely with respect to F, introducing six degrees of freedom. However, unlike the QuaternionFloatingJoint, the orientation of M relative to F is parameterized with roll-pitch-yaw angles (see warning below). The generalized coordinates q for this joint are the three orientation angles followed by three generalized positions to describe the translation of frame M's origin Mo in F with a position vector p_FM. As generalized velocities, we use the angular velocity w_FM of frame M in F (not the orientation angle time derivatives q̇) and the linear velocity v_FM of frame M's origin Mo in frame F.

Warning
Any three-parameter representation of orientation necessarily has a singularity somewhere. In this case, the singularity occurs when the pitch angle (second generalized coordinate q) is at π/2 + kπ (for any integer k), and numerical issues may occur when near one of those configurations. If you can't be sure your simulation will avoid the singularities, consider using the singularity-free QuaternionFloatingJoint instead.
Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Types

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

Public Member Functions

 RpyFloatingJoint (const std::string &name, const Frame< T > &frame_on_parent, const Frame< T > &frame_on_child, double angular_damping=0.0, double translational_damping=0.0)
 Constructor to create an rpy floating joint between two bodies so that frame F attached to the parent body P and frame M attached to the child body B move freely relative to one another. More...
 
 ~RpyFloatingJoint () final
 
const std::string & type_name () const final
 Returns the name of this joint type: "rpy_floating". More...
 
double default_angular_damping () const
 Returns this joint's default angular damping constant in N⋅m⋅s. More...
 
double default_translational_damping () const
 Returns this joint's default translational damping constant in N⋅s/m. More...
 
Does not allow copy, move, or assignment
 RpyFloatingJoint (const RpyFloatingJoint &)=delete
 
RpyFloatingJointoperator= (const RpyFloatingJoint &)=delete
 
 RpyFloatingJoint (RpyFloatingJoint &&)=delete
 
RpyFloatingJointoperator= (RpyFloatingJoint &&)=delete
 
Context-dependent value access

Functions in this section are given a Context and either get from it, or set in it, quantities relevant to this RpyFloatingJoint.

These functions can only be called after MultibodyPlant::Finalize().

Vector3< T > get_angles (const Context< T > &context) const
 Gets the roll-pitch-yaw rotation angles of this joint from context. More...
 
const RpyFloatingJoint< T > & set_angles (Context< T > *context, const Vector3< T > &angles) const
 Sets the context so that the generalized coordinates corresponding to the roll-pitch-yaw rotation angles of this joint equals angles. More...
 
const RpyFloatingJoint< T > & SetOrientation (systems::Context< T > *context, const math::RotationMatrix< T > &R_FM) const
 Sets the roll-pitch-yaw angles in context so this Joint's orientation is consistent with the given R_FM rotation matrix. More...
 
Vector3< T > get_translation (const systems::Context< T > &context) const
 Returns the translation (position vector) p_FM of the child frame M's origin Mo as measured and expressed in the parent frame F. More...
 
const RpyFloatingJoint< T > & SetTranslation (systems::Context< T > *context, const Vector3< T > &p_FM) const
 Sets context to store the translation (position vector) p_FM of frame M's origin Mo measured and expressed in frame F. More...
 
math::RigidTransform< T > GetPose (const systems::Context< T > &context) const
 Returns the pose X_FM of the outboard frame M as measured and expressed in the inboard frame F. More...
 
const RpyFloatingJoint< T > & SetPose (systems::Context< T > *context, const math::RigidTransform< T > &X_FM) const
 Sets context to store X_FM the pose of frame M measured and expressed in frame F. 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 RpyFloatingJoint< 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...
 
Vector3< T > get_translational_velocity (const systems::Context< T > &context) const
 Retrieves from context the translational velocity v_FM of the child frame M's origin as measured and expressed in the parent frame F. More...
 
const RpyFloatingJoint< T > & set_translational_velocity (systems::Context< T > *context, const Vector3< T > &v_FM) const
 Sets in context the state for this joint so that the translational velocity of the child frame M's origin in the parent frame F is v_FM. More...
 
Random distribution setters

These functions can only be called after MultibodyPlant::Finalize().

void set_random_angles_distribution (const Vector3< symbolic::Expression > &angles)
 Sets the random distribution from which the roll-pitch-yaw orientation angles of this joint will be randomly sampled. More...
 
void set_random_translation_distribution (const Vector3< symbolic::Expression > &p_FM)
 Sets the random distribution that the translation vector of this joint will be randomly sampled from. More...
 
Default pose access

Functions in this section set or get the default values for the pose states q (rpy angles and translation vector) of this RpyFloatingJoint.

These are stored directly in the joint rather than in a Context and are used to initialize Contexts. Note that the default velocities v are always zero.

Vector3< doubleget_default_angles () const
 Gets the default angles for this joint. More...
 
void set_default_angles (const Vector3< double > &angles)
 Sets the default roll-pitch-yaw angles of this joint. More...
 
Vector3< doubleget_default_translation () const
 Gets the default translation (position vector) p_FM for this joint. More...
 
void set_default_translation (const Vector3< double > &p_FM)
 Sets the default translation (position vector) p_FM of this joint. 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
 Returns the position lower limits. More...
 
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...
 
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 generalized position coordinates q₀ to default_positions. More...
 
const VectorX< double > & default_positions () const
 Returns the default generalized position coordinates q₀. More...
 
void SetPositions (systems::Context< T > *context, const Eigen::Ref< const VectorX< T >> &positions) const
 Sets in the given context the generalized position coordinates q for this joint to positions. More...
 
Eigen::Ref< const VectorX< T > > GetPositions (const systems::Context< T > &context) const
 Returns the current value in the given context of the generalized coordinates q for this joint. More...
 
void SetVelocities (systems::Context< T > *context, const Eigen::Ref< const VectorX< T >> &velocities) const
 Sets in the given context the generalized velocity coordinates v for this joint to velocities. More...
 
Eigen::Ref< const VectorX< T > > GetVelocities (const systems::Context< T > &context) const
 Returns the current value in the given context of the generalized velocities v for this joint. 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 SetPose (systems::Context< T > *context, const math::RigidTransform< T > &X_FM) const
 Sets in the given context this joint's 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< T > GetPose (const systems::Context< T > &context) const
 Returns this joint's current pose using its position coordinates q taken from the given context and converting that to a RigidTransform X_FM(q). More...
 
void SetSpatialVelocity (systems::Context< T > *context, const SpatialVelocity< T > &V_FM) const
 Sets in the given context this joint's generalized velocities v such that the spatial velocity of the child frame M in the parent frame F best matches the given spatial velocity. More...
 
SpatialVelocity< T > GetSpatialVelocity (const systems::Context< T > &context) const
 Given the generalized positions q and generalized velocities v for this joint in the given context, returns the cross-joint spatial velocity V_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...
 
void SetPosePair (systems::Context< T > *context, const Quaternion< T > &q_FM, const Vector3< T > &p_FM) const
 (Advanced) This is the same as SetPose() except it takes the pose as a (quaternion, translation vector) pair. More...
 
std::pair< Eigen::Quaternion< T >, Vector3< T > > GetPosePair (const systems::Context< T > &context) const
 (Advanced) This is the same as GetPose() except it returns this joint's pose in the given context 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 [] = "rpy_floating"
 The name for this Joint type. It resolves to "rpy_floating". More...
 

Protected Member Functions

void DoAddInOneForce (const systems::Context< T > &, int, const T &, MultibodyForces< T > *) const final
 Joint<T> override called through public NVI, Joint::AddInForce(). More...
 
void DoAddInDamping (const systems::Context< T > &context, MultibodyForces< T > *forces) const final
 Joint<T> override called through public NVI, Joint::AddInDamping(). More...
 
- Protected Member Functions inherited from Joint< T >
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...
 
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 RpyFloatingJoint
 

Member Typedef Documentation

◆ Context

using Context = systems::Context<Scalar>

Constructor & Destructor Documentation

◆ RpyFloatingJoint() [1/3]

RpyFloatingJoint ( const RpyFloatingJoint< T > &  )
delete

◆ RpyFloatingJoint() [2/3]

RpyFloatingJoint ( RpyFloatingJoint< T > &&  )
delete

◆ RpyFloatingJoint() [3/3]

RpyFloatingJoint ( const std::string &  name,
const Frame< T > &  frame_on_parent,
const Frame< T > &  frame_on_child,
double  angular_damping = 0.0,
double  translational_damping = 0.0 
)

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

See this class's documentation for further details on the definition of these frames and the generalized positions q and generalized velocities v for this joint. 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]angular_dampingViscous damping coefficient in N⋅m⋅s for the angular component of this joint's velocity, used to model losses within the joint. See documentation of default_angular_damping() for details on modeling of the damping force.
[in]translational_dampingViscous damping coefficient in N⋅s/m for the translational component of this joint's velocity, used to model losses within the joint. See documentation of default_translational_damping() for details on modeling of the damping force.
Exceptions
std::exceptionif angular_damping is negative.
std::exceptionif translational_damping is negative.

◆ ~RpyFloatingJoint()

~RpyFloatingJoint ( )
final

Member Function Documentation

◆ default_angular_damping()

double default_angular_damping ( ) const

Returns this joint's default angular 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).

◆ default_translational_damping()

double default_translational_damping ( ) const

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

The damping force (in N) is modeled as f = -damping⋅v i.e. opposing motion, with v the translational velocity of frame M in F (see get_translational_velocity()) and f the force on child body B at Mo.

◆ DoAddInDamping()

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

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

Therefore arguments were already checked to be valid. This method adds into the translational component of forces for this joint a dissipative force according to the viscous law f = -d⋅v, with d the damping coefficient (see default_translational_damping()). This method also adds into the angular component of forces for this joint a dissipative torque according to the viscous law τ = -d⋅ω, with d the damping coefficient (see default_angular_damping()).

Reimplemented from Joint< T >.

◆ DoAddInOneForce()

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

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

Adding forces per-dof for this joint is not supported. Therefore, this method throws an exception if invoked.

Implements Joint< T >.

◆ get_angles()

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

Gets the roll-pitch-yaw rotation angles of this joint from context.

The orientation R_FM of the child frame M in parent frame F is parameterized with roll-pitch-yaw angles (also known as space-fixed x-y-z Euler angles and extrinsic angles). That is, the angles θr, θp, θy, correspond to a sequence of rotations about the Fx, Fy, and Fz 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 Fx, Fy and Fz axes respectively. Zero θr, θp, θy angles corresponds to frames F and M having the same orientation (their origins may still be separated). 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).
Parameters
[in]contextA Context for the MultibodyPlant this joint belongs to.
Return values
anglesThe 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]contextA Context for the MultibodyPlant 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.

Return values
anglesThe default roll-pitch-yaw angles as a Vector3.

◆ get_default_translation()

Vector3<double> get_default_translation ( ) const

Gets the default translation (position vector) p_FM for this joint.

Return values
p_FMThe default translation of this joint.

◆ get_translation()

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

Returns the translation (position vector) p_FM of the child frame M's origin Mo as measured and expressed in the parent frame F.

Refer to the class documentation for details.

Parameters
[in]contextA Context for the MultibodyPlant this joint belongs to.
Return values
p_FMThe position vector of frame M's origin in frame F.

◆ get_translational_velocity()

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

Retrieves from context the translational velocity v_FM of the child frame M's origin as measured and expressed in the parent frame F.

Parameters
[in]contextA Context for the MultibodyPlant this joint belongs to.
Return values
v_FMA vector in ℝ³ with the translational velocity of the origin of 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.

◆ GetPose()

math::RigidTransform<T> GetPose ( const systems::Context< T > &  context) const

Returns the pose X_FM of the outboard frame M as measured and expressed in the inboard frame F.

Refer to the documentation for this class for details.

Parameters
[in]contextA Context for the MultibodyPlant this joint belongs to.
Return values
X_FMThe pose of frame M in frame F.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ set_angles()

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

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

Parameters
[in,out]contextA Context for the MultibodyPlant this joint belongs to.
[in]anglesAngles in radians to be stored in context ordered as θr, θp, θy.
Warning
See class documentation for discussion of singular configurations.
Returns
a constant reference to this joint.
See also
get_angles() for details

◆ set_angular_velocity()

const RpyFloatingJoint<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
[in,out]contextA Context for the MultibodyPlant 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 roll-pitch-yaw angles of this joint.

Parameters
[in]anglesthe desired default angles of the joint
Warning
See class documentation for discussion of singular configurations.

◆ set_default_translation()

void set_default_translation ( const Vector3< double > &  p_FM)

Sets the default translation (position vector) p_FM of this joint.

Parameters
[in]p_FMThe desired default translation of the joint.

◆ set_random_angles_distribution()

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

Sets the random distribution from which the roll-pitch-yaw orientation angles of this joint will be randomly sampled.

See the RpyFloatingJoint class documentation for details on the orientation representation. If a translation distribution has already been set with stochastic variables, it will remain so. Otherwise translation will be set to this joint's zero configuration.

Warning
Watch for random pitch angles near the singular configuration for this joint (see class documentation).

◆ set_random_translation_distribution()

void set_random_translation_distribution ( const Vector3< symbolic::Expression > &  p_FM)

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

See the RpyFloatingJoint class documentation for details on the translation representation. If an angles distribution has has already been set with stochastic variables, it will remain so. Otherwise angles will be set to this joint's zero configuration.

◆ set_translational_velocity()

const RpyFloatingJoint<T>& set_translational_velocity ( systems::Context< T > *  context,
const Vector3< T > &  v_FM 
) const

Sets in context the state for this joint so that the translational velocity of the child frame M's origin in the parent frame F is v_FM.

Parameters
[in,out]contextA Context for the MultibodyPlant this joint belongs to.
[in]v_FMA vector in ℝ³ with the translational velocity of the child frame M's origin 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.

◆ SetOrientation()

const RpyFloatingJoint<T>& SetOrientation ( systems::Context< T > *  context,
const math::RotationMatrix< T > &  R_FM 
) const

Sets the roll-pitch-yaw angles in context so this Joint's orientation is consistent with the given R_FM rotation matrix.

Parameters
[in,out]contextA Context for the MultibodyPlant this joint belongs to.
[in]R_FMThe rotation matrix giving the orientation of frame M in frame F.
Warning
See class documentation for discussion of singular configurations.
Returns
a constant reference to this joint.

◆ SetPose()

const RpyFloatingJoint<T>& SetPose ( systems::Context< T > *  context,
const math::RigidTransform< T > &  X_FM 
) const

Sets context to store X_FM the pose of frame M measured and expressed in frame F.

Parameters
[in,out]contextA Context for the MultibodyPlant this joint belongs to.
[in]X_FMThe desired pose of frame M in frame F to be stored in context.
Warning
See class documentation for discussion of singular configurations.
Returns
a constant reference to this joint.

◆ SetTranslation()

const RpyFloatingJoint<T>& SetTranslation ( systems::Context< T > *  context,
const Vector3< T > &  p_FM 
) const

Sets context to store the translation (position vector) p_FM of frame M's origin Mo measured and expressed in frame F.

Parameters
[in,out]contextA Context for the MultibodyPlant this joint belongs to.
[in]p_FMThe desired position of frame M's origin in frame F, to be stored in context.
Returns
a constant reference to this joint.

◆ type_name()

const std::string& type_name ( ) const
finalvirtual

Returns the name of this joint type: "rpy_floating".

Implements Joint< T >.

Friends And Related Function Documentation

◆ RpyFloatingJoint

friend class RpyFloatingJoint
friend

Member Data Documentation

◆ kTypeName

const char kTypeName = "rpy_floating"
static

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


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