template<typename T>
class drake::multibody::QuaternionFloatingJoint< T >
This Joint allows two bodies to move freely relatively 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 translate and rotate freely with respect to F, introducing six degrees of freedom. This Joint introduces four generalized positions to describe the orientation R_FM
of frame M in F with a quaternion q_FM
, and three generalized positions to describe the translation of frame M's origin in F with a position vector p_FM
. The seven entries of the configuration vector q are ordered (q_FM, p_FM)
with the quaternion, ordered wxyz (scalar then vector), preceding the translation vector. As generalized velocities, this Joint introduces the angular velocity w_FM
of frame M in F and the linear velocity v_FM
of frame M's origin in frame F, ordered (w_FM, v_FM)
.
- Template Parameters
-
|
| QuaternionFloatingJoint (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 for a QuaternionFloatingJoint granting six degrees of freedom to an outboard frame M attached to the child body B with respect to an inboard frame F attached to the parent body P. More...
|
|
| ~QuaternionFloatingJoint () override |
|
const std::string & | type_name () const override |
| Returns the name of this joint type: "quaternion_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...
|
|
|
| QuaternionFloatingJoint (const QuaternionFloatingJoint &)=delete |
|
QuaternionFloatingJoint & | operator= (const QuaternionFloatingJoint &)=delete |
|
| QuaternionFloatingJoint (QuaternionFloatingJoint &&)=delete |
|
QuaternionFloatingJoint & | operator= (QuaternionFloatingJoint &&)=delete |
|
|
Quaternion< T > | get_quaternion (const systems::Context< T > &context) const |
| Gets the quaternion q_FM that represents the orientation of outboard frame M in the inboard frame F. More...
|
|
Vector3< T > | get_translation (const systems::Context< T > &context) const |
| Returns the position vector p_FoMo_F from Fo (inboard frame F's origin) to Mo (outboard frame M's origin), expressed in inboard 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...
|
|
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...
|
|
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 QuaternionFloatingJoint< T > & | SetQuaternion (systems::Context< T > *context, const Quaternion< T > &q_FM) const |
| Sets context so that the orientation of frame M in F is given by the input quaternion q_FM . More...
|
|
const QuaternionFloatingJoint< T > & | SetOrientation (systems::Context< T > *context, const math::RotationMatrix< T > &R_FM) const |
| Sets the quaternion in context so this joint's orientation is consistent with the given R_FM rotation matrix. More...
|
|
const QuaternionFloatingJoint< T > & | SetTranslation (systems::Context< T > *context, const Vector3< T > &p_FM) const |
| For this joint, stores the position vector p_FM in context . More...
|
|
const QuaternionFloatingJoint< 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...
|
|
const QuaternionFloatingJoint< 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...
|
|
const QuaternionFloatingJoint< 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...
|
|
|
void | set_random_translation_distribution (const Vector3< symbolic::Expression > &p_FM) |
| For this joint, sets the random distribution that the translation of this joint will be randomly sampled from. More...
|
|
void | set_random_quaternion_distribution (const Eigen::Quaternion< symbolic::Expression > &q_FM) |
| (Advanced) Sets the random distribution that the orientation of this joint will be randomly sampled from. More...
|
|
void | set_random_quaternion_distribution_to_uniform () |
| Sets the random distribution such that the orientation of this joint will be randomly sampled using uniformly sampled rotations. More...
|
|
|
Quaternion< double > | get_default_quaternion () const |
| Gets the default quaternion q_FM for this joint. More...
|
|
Vector3< double > | get_default_translation () const |
| Returns this joint's default translation as the position vector p_FoMo_F from Fo (inboard frame F's origin) to Mo (outboard frame M's origin), expressed in inboard frame F. More...
|
|
|
void | set_default_quaternion (const Quaternion< double > &q_FM) |
| Sets the default quaternion q_FM of this joint. More...
|
|
void | set_default_translation (const Vector3< double > &p_FM) |
| Sets this joint's default position vector p_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...
|
|
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 |
|
Joint & | operator= (const Joint &)=delete |
|
| Joint (Joint &&)=delete |
|
Joint & | operator= (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< double > | GetDefaultPose () 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 |
|
MultibodyElement & | operator= (const MultibodyElement &)=delete |
|
| MultibodyElement (MultibodyElement &&)=delete |
|
MultibodyElement & | operator= (MultibodyElement &&)=delete |
|
|
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 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 JointImplementation & | get_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...
|
|