template<typename T>
class drake::multibody::DoorHinge< T >
This ForceElement models a revolute DoorHinge joint that could exhibit different force/torque characteristics at different states due to the existence of different type of torques on the joint.
This class implements a "christmas tree" accumulation of these different torques in an empirical and unprincipled way. Specifically, different curves are assigned to different torques to mimic their evolution based on the joint state and some prespecified parameters.
Torques considered in this implementation include:
- torsional spring torque (τ_ts) – position dependent
- catch torque (τ_c) – position dependent
- dynamic friction torque (τ_df) – velocity dependent
- static friction torque (τ_sf) – velocity dependent
- viscous friction torque (τ_vf) – velocity dependent
We then implement two curves to approximate the progression of different torques. A curve s(t, x) = tanh(x/t) uses the tanh function to approximate a step curve ({x<0: -1 ; x>0: 1}) outside of -t < x < t. The curve doublet(t, x) = 2 * s * (1 − s²) is the second derivative of s scaled by -t², which yields a lump at negative x that integrates to -1 and a lump at positive x that integrates to 1. Finally, the total external torque on the hinge joint would be:
τ = τ_ts + τ_c + τ_df + τ_sf + τ_vf.
where τ_ts = -k_ts * (q − qs₀), τ_c = k_c * doublet(qc₀/2, q − qc₀/2), τ_df = -k_df * s(k_q̇₀, q̇), τ_sf = -k_sf * doublet(k_q̇₀, q̇) and τ_vf = -k_vf * q̇. The door is assumed to be closed at q=0, opening in the positive-q direction. Note that, the sign of the torques depends on two elements: one is the sign of the torque related constants and another one is the sign of the assigned curves. For example, as defined above, the static friction torque τ_sf should be opposite to the direction of the velocity q̇. The catch torque τ_c should be negative when q < qc₀/2 and positive otherwise. This class applies all hinge-originating forces, so it can be used instead of the SDF viscous damping. The users could change the values of these different elements to obtain different characteristics for the DoorHinge joint that the users want to model. A jupyter notebook tool is also provided to help the users visualize the curves and design parameters. Run bazel run //bindings/pydrake/multibody:examples/door_hinge_inspector to bring up the notebook.
To give an example, a common dishwasher door has a frictional torque sufficient for it to rest motionless at any angle, a catch at the top to hold it in place, a dashpot (viscous friction source) to prevent it from swinging too fast, and a spring to counteract some of its mass. Two figures are provided to illustrate the dishwasher DoorHinge torque with the given default parameters. Figure 1 shows the static characteristic of the dishwasher door. At q = 0, there exists a negative catch torque to prevent the door from moving. After that, the torsional spring torque will dominate to compensate part of the door gravity. Figure 2 shows the dynamic feature of the dishwasher door at q = 30 deg. It shows the door can be closed easily since the torque is small when the velocity is negative. However, whenever the door intends to open further, there will be a counter torque to prevent that movement, which therefore keeps the door at rest. Note that, due to the gravity, the dishwasher door will be fully open eventually. This process can be really slow because of the default motion_threshold is set to be very small. You can change the motion_threshold parameter to adjust the time.
- Template Parameters
-
|
| | DoorHinge (const RevoluteJoint< T > &joint, const DoorHingeConfig &config) |
| | Constructs a hinge force element with parameters config applied to the specified joint.
|
| | ~DoorHinge () override |
| const RevoluteJoint< T > & | joint () const |
| const DoorHingeConfig & | config () const |
| T | CalcPotentialEnergy (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &) const override |
| | (Advanced) Calculates the potential energy currently stored given the configuration provided in context.
|
| T | CalcConservativePower (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &, const internal::VelocityKinematicsCache< T > &) const override |
| | (Advanced) Calculates and returns the power generated by conservative force elements or zero if this force element is non-conservative.
|
| T | CalcNonConservativePower (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &, const internal::VelocityKinematicsCache< T > &) const override |
| | (Advanced) Calculates the rate at which mechanical energy is being generated (positive) or dissipated (negative) other than by conversion between potential and kinetic energy.
|
| | DoorHinge (const DoorHinge &)=delete |
| DoorHinge & | operator= (const DoorHinge &)=delete |
| | DoorHinge (DoorHinge &&)=delete |
| DoorHinge & | operator= (DoorHinge &&)=delete |
Convenience functions for evaluating DoorHinge operations without worrying about context-related issues.
|
| T | CalcHingeFrictionalTorque (const T &angular_rate) const |
| | Calculates the total frictional torque with the given angular_rate and the internal DoorHingeConfig.
|
| T | CalcHingeSpringTorque (const T &angle) const |
| | Calculate the total spring related torque with the given angle and the internal DoorHingeConfig.
|
| T | CalcHingeTorque (const T &angle, const T &angular_rate) const |
| | Calculate the total torque with the given angle and angular_rate and the internal DoorHingeConfig.
|
| T | CalcHingeConservativePower (const T &angle, const T &angular_rate) const |
| | Calculate the total conservative power with the given angle, angular_rate, and the internal DoorHingeConfig.
|
| T | CalcHingeNonConservativePower (const T &angular_rate) const |
| | Calculate the total non-conservative power with the given angular_rate and the internal DoorHingeConfig.
|
| T | CalcHingeStoredEnergy (const T &angle) const |
| | Calculate the total potential energy of the DoorHinge ForceElement with the given angle and the internal DoorHingeConfig.
|
| Public Member Functions inherited from ForceElement< T > |
| | ForceElement (ModelInstanceIndex model_instance) |
| | Default constructor for a generic force element.
|
| | ~ForceElement () override |
| ForceElementIndex | index () const |
| | Returns this element's unique index.
|
| void | CalcAndAddForceContribution (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &pc, const internal::VelocityKinematicsCache< T > &vc, MultibodyForces< T > *forces) const |
| | (Advanced) Computes the force contribution for this force element and adds it to the output arrays of forces.
|
| | ForceElement (const ForceElement &)=delete |
| ForceElement & | operator= (const ForceElement &)=delete |
| | ForceElement (ForceElement &&)=delete |
| ForceElement & | operator= (ForceElement &&)=delete |
| 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.
|
| template<typename = void> |
| const MultibodyPlant< T > & | GetParentPlant () const |
| | Returns the MultibodyPlant that owns this MultibodyElement.
|
| void | DeclareParameters (internal::MultibodyTreeSystem< T > *tree_system) |
| | Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time.
|
| void | SetDefaultParameters (systems::Parameters< T > *parameters) const |
| | Sets default values of parameters belonging to each MultibodyElement in parameters at a call to MultibodyTreeSystem::SetDefaultParameters().
|
| void | DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system) |
| | Declares MultibodyTreeSystem discrete states.
|
| void | DeclareCacheEntries (internal::MultibodyTreeSystem< T > *tree_system) |
| | (Advanced) Declares all cache entries needed by this element.
|
| bool | is_ephemeral () const |
| | Returns true if this MultibodyElement was added during Finalize() rather than something a user added.
|
| void | set_is_ephemeral (bool is_ephemeral) |
| | (Internal use only) Sets the is_ephemeral flag to the indicated value.
|
| | MultibodyElement (const MultibodyElement &)=delete |
| MultibodyElement & | operator= (const MultibodyElement &)=delete |
| | MultibodyElement (MultibodyElement &&)=delete |
| MultibodyElement & | operator= (MultibodyElement &&)=delete |
|
| void | DoCalcAndAddForceContribution (const systems::Context< T > &context, const internal::PositionKinematicsCache< T > &, const internal::VelocityKinematicsCache< T > &, MultibodyForces< T > *forces) const override |
| | This method is called only from the public non-virtual CalcAndAddForceContributions() which will already have error-checked the parameters so you don't have to.
|
| std::unique_ptr< ForceElement< double > > | DoCloneToScalar (const internal::MultibodyTree< double > &) const override |
| | Clones this ForceElement (templated on T) to a mobilizer templated on double.
|
| std::unique_ptr< ForceElement< AutoDiffXd > > | DoCloneToScalar (const internal::MultibodyTree< AutoDiffXd > &) const override |
| | Clones this ForceElement (templated on T) to a mobilizer templated on AutoDiffXd.
|
| std::unique_ptr< ForceElement< symbolic::Expression > > | DoCloneToScalar (const internal::MultibodyTree< symbolic::Expression > &) const override |
| std::unique_ptr< ForceElement< T > > | DoShallowClone () const override |
| | NVI for ShallowClone().
|
| Protected Member Functions inherited from ForceElement< T > |
| virtual void | DoDeclareForceElementParameters (internal::MultibodyTreeSystem< T > *) |
| | Called by DoDeclareParameters().
|
| virtual void | DoSetDefaultForceElementParameters (systems::Parameters< T > *) const |
| | Called by DoSetDefaultParameters().
|
| 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.
|
| | MultibodyElement (ModelInstanceIndex model_instance) |
| | Constructor which allows specifying a model instance.
|
| | MultibodyElement (ModelInstanceIndex model_instance, int64_t index) |
| | Both the model instance and element index are specified.
|
| template<typename ElementIndexType> |
| ElementIndexType | index_impl () const |
| | Returns this element's unique index.
|
| template<typename ElementOrdinalType = int64_t> |
| ElementOrdinalType | ordinal_impl () const |
| | Returns this element's unique ordinal.
|
| const internal::MultibodyTree< T > & | get_parent_tree () const |
| | Returns a constant reference to the parent MultibodyTree that owns this element.
|
| const internal::MultibodyTreeSystem< T > & | GetParentTreeSystem () const |
| | Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element.
|
| void | SetTopology () |
| | (Internal use only) Gives MultibodyElement-derived objects the opportunity to set data members that depend on topology and coordinate assignments having been finalized.
|
| virtual void | DoDeclareDiscreteState (internal::MultibodyTreeSystem< T > *) |
| | Implementation of the NVI DeclareDiscreteState().
|
| virtual void | DoDeclareCacheEntries (internal::MultibodyTreeSystem< T > *) |
| | Derived classes must override this method to declare cache entries needed by this element.
|
| 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().
|
| 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().
|
| systems::DiscreteStateIndex | DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system, const VectorX< T > &model_value) |
| | To be used by MultibodyElement-derived objects when declaring discrete states in their implementation of DoDeclareDiscreteStates().
|
| systems::CacheEntry & | DeclareCacheEntry (internal::MultibodyTreeSystem< T > *tree_system, std::string description, systems::ValueProducer value_producer, std::set< systems::DependencyTicket > prerequisites_of_calc) |
| | To be used by MultibodyElement-derived objects when declaring cache entries in their implementation of DoDeclareCacheEntries().
|
| bool | has_parent_tree () const |
| | Returns true if this multibody element has a parent tree, otherwise false.
|