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:
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.
T | The scalar type, which must be one of the default scalars. |
#include <drake/multibody/tree/door_hinge.h>
Public Member Functions | |
DoorHinge (const RevoluteJoint< T > &joint, const DoorHingeConfig &config) | |
Constructs a hinge force element with parameters config applied to the specified joint . More... | |
~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 . More... | |
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. More... | |
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. More... | |
Does not allow copy, move, or assignment | |
DoorHinge (const DoorHinge &)=delete | |
DoorHinge & | operator= (const DoorHinge &)=delete |
DoorHinge (DoorHinge &&)=delete | |
DoorHinge & | operator= (DoorHinge &&)=delete |
Advanced Functions | |
T | CalcHingeFrictionalTorque (const T &angular_rate) const |
Calculates the total frictional torque with the given angular_rate and the internal DoorHingeConfig. More... | |
T | CalcHingeSpringTorque (const T &angle) const |
Calculate the total spring related torque with the given angle and the internal DoorHingeConfig. More... | |
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. More... | |
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. More... | |
T | CalcHingeNonConservativePower (const T &angular_rate) const |
Calculate the total non-conservative power with the given angular_rate and the internal DoorHingeConfig. More... | |
T | CalcHingeStoredEnergy (const T &angle) const |
Calculate the total potential energy of the DoorHinge ForceElement with the given angle and the internal DoorHingeConfig. More... | |
Public Member Functions inherited from ForceElement< T > | |
ForceElement (ModelInstanceIndex model_instance) | |
Default constructor for a generic force element. More... | |
~ForceElement () override | |
ForceElementIndex | index () const |
Returns this element's unique index. More... | |
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. More... | |
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. 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 |
Protected Member Functions | |
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. More... | |
std::unique_ptr< ForceElement< double > > | DoCloneToScalar (const internal::MultibodyTree< double > &) const override |
Clones this ForceElement (templated on T) to a mobilizer templated on double . More... | |
std::unique_ptr< ForceElement< AutoDiffXd > > | DoCloneToScalar (const internal::MultibodyTree< AutoDiffXd > &) const override |
Clones this ForceElement (templated on T) to a mobilizer templated on AutoDiffXd. More... | |
std::unique_ptr< ForceElement< symbolic::Expression > > | DoCloneToScalar (const internal::MultibodyTree< symbolic::Expression > &) const override |
Protected Member Functions inherited from ForceElement< T > | |
virtual void | DoDeclareForceElementParameters (internal::MultibodyTreeSystem< T > *) |
Called by DoDeclareParameters(). More... | |
virtual void | DoSetDefaultForceElementParameters (systems::Parameters< T > *) const |
Called by DoSetDefaultParameters(). 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 | |
class | DoorHingeTest |
template<typename U > | |
class | DoorHinge |
DoorHinge | ( | const RevoluteJoint< T > & | joint, |
const DoorHingeConfig & | config | ||
) |
Constructs a hinge force element with parameters config
applied to the specified joint
.
It will throw an exception if the DoorHingeConfig is invalid.
|
override |
|
overridevirtual |
(Advanced) Calculates and returns the power generated by conservative force elements or zero if this
force element is non-conservative.
This quantity is defined to be positive when the potential energy is decreasing. In other words, if PE
is the potential energy as defined by CalcPotentialEnergy(), then the conservative power, Pc
, is Pc = -d(PE)/dt
.
Implements ForceElement< T >.
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 CalcHingeFrictionalTorque | ( | const T & | angular_rate | ) | const |
Calculates the total frictional torque with the given 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 CalcHingeSpringTorque | ( | const T & | angle | ) | const |
Calculate the total spring related torque with the given angle
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.
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.
|
overridevirtual |
(Advanced) Calculates the rate at which mechanical energy is being generated (positive) or dissipated (negative) other than by conversion between potential and kinetic energy.
Integrating this quantity yields work W, and the total energy E = PE + KE - W
should be conserved by any physically-correct model, to within integration accuracy of W.
Implements ForceElement< T >.
|
overridevirtual |
(Advanced) Calculates the potential energy currently stored given the configuration provided in context
.
Non-conservative force elements will return zero.
[in] | context | The context containing the state of the MultibodyTree model. |
[in] | pc | A position kinematics cache object already updated to be in sync with context . |
pc
must have been previously updated with a call to CalcPositionKinematicsCache().this
force element. For non-conservative force models, zero.Implements ForceElement< T >.
const DoorHingeConfig& config | ( | ) | const |
|
overrideprotectedvirtual |
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.
Refer to the documentation for CalcAndAddForceContribution() for details describing the purpose and parameters of this method. It assumes forces
to be a valid pointer to a MultibodyForces object compatible with the MultibodyTree model owning this
force element.
pc
must have been previously updated with a call to CalcPositionKinematicsCache(). vc
must have been previously updated with a call to CalcVelocityKinematicsCache(). Implements ForceElement< T >.
|
overrideprotectedvirtual |
Clones this ForceElement (templated on T) to a mobilizer templated on double
.
Implements ForceElement< T >.
|
overrideprotectedvirtual |
Clones this ForceElement (templated on T) to a mobilizer templated on AutoDiffXd.
Implements ForceElement< T >.
|
overrideprotectedvirtual |
Implements ForceElement< T >.
const RevoluteJoint<T>& joint | ( | ) | const |
|
friend |
|
friend |