This ForceElement models a massless flexible bushing that connects a frame A of a link (body) L0 to a frame C of a link (body) L1.
The bushing can apply a torque and force due to stiffness (spring) and dissipation (damper) properties. Frame B is the bushing frame whose origin Bo is halfway between Ao (A's origin) and Co (C's origin) and whose unit vectors ππ±, ππ², ππ³ are "halfway" (in an angle-axis sense) between the unit vectors of frame A and frame C. Frame B is a "floating" frame in the sense that it is calculated from the position and orientation of frames A and C (B is not welded to the bushing).
The set of forces on frame C from the bushing is equivalent to a torque π on frame C and a force π applied to a point Cp of C. The set of forces on frame A from the bushing is equivalent to a torque βπ on frame A and a force βπ applied to a point Ap of A. Points Ap and Cp are coincident with Bo (frame B's origin).
This "quasi-symmetric" bushing force/torque model was developed at Toyota Research Institute and has advantages compared to traditional bushing models because it employs a bushing-centered "symmetric" frame B and it ensures the moment of βπ on A about Ao is equal to the moment of π on C about Co. Traditional models differ as they lack a "symmetric" frame B and apply βπ at Ao, which means the moment of βπ on A about Ao is always zero. Note: This bushing model is not fully symmetric since the orientation between frames A and C is parameterized with roll-pitch-yaw angles [qβ qβ qβ]. Since these angles have an inherent sequence, they are not mathematically symmetric.
The torque model depends on spring-damper "gimbal" torques Ο β [Οβ Οβ Οβ]
which themselves depend on roll-pitch-yaw angles q β [qβ qβ qβ]
and rates qΜ = [qΜβ qΜβ qΜβ]
via a diagonal torque-stiffness matrix Kβββ and a diagonal torque-damping matrix Dβββ as
β Οβ β βkβ 0 0β β qβ β βdβ 0 0β β qΜβ β Ο β | Οβ | = β | 0 kβ 0| | qβ | β | 0 dβ 0| | qΜβ | β Οβ β β 0 0 kββ β qβ β β 0 0 dββ β qΜβ β
where kβ, kβ, kβ and dβ, dβ, dβ are torque stiffness and damping constants and must have non-negative values.
(Ο β π)
. The bushing model for the net force π on frame C from the bushing depends on scalars x, y, z which are defined so π« (the position vector from Ao to Co) can be expressed in frame B as π« β p_AoCo = [x y z]Κ = x ππ± + y ππ² + z ππ³
. The model for π uses a diagonal force-stiffness matrix Kxyα΄’, a diagonal force-damping matrix Dxyα΄’, and defines fx, fy, fz so π = [fx fy fz]Κ
.
β fx β βkx 0 0β β x β βdx 0 0β β xΜ β | fy | = β | 0 ky 0| | y | β | 0 dy 0| | yΜ | β fz β β 0 0 kzβ β z β β 0 0 dzβ β zΜ β
where kx, ky, kz and dx, dy, dz are force stiffness and damping constants and must have non-negative values.
This bushing's constructor sets the torque stiffness/damping constants [kβ kβ kβ]
and [dβ dβ dβ]
and the force stiffness/damping constants [kx ky kz]
and [dx dy dz]
. The examples below demonstrate how to model various joints that have a flexible (e.g., rubber) mount. The damping values below with ? may be set to 0 or a reasonable positive number.
Bushing type | torque constants | force constants |
---|---|---|
z-axis revolute joint | kβββ = [kβ kβ 0] | kxyz = [kx ky kz] |
dβββ = [dβ dβ ?] | dxyz = [dx dy dz] | |
x-axis prismatic joint | kβββ = [kβ kβ kβ] | kxyz = [0 ky kz] |
dβββ = [dβ dβ dβ] | dxyz = [? dy dz] | |
Ball and socket joint | kβββ = [0 0 0] | kxyz = [kx ky kz] |
dβββ = [? ? ?] | dxyz = [dx dy dz] | |
Weld/fixed joint | kβββ = [kβ kβ kβ] | kxyz = [kx ky kz] |
dβββ = [dβ dβ dβ] | dxyz = [dx dy dz] |
Angles qβ, qβ, qβ are calculated from frame C's orientation relative to frame A, with [βΟ < qβ β€ Ο, βΟ/2 β€ qβ β€ Ο/2, βΟ < qβ β€ Ο]
, hence, there is no angle wrapping and torque stiffness has a limited range. Gimbal torques Ο can be discontinuous if one of qβ, qβ, qβ is discontinuous and its associated torque spring constant is nonzero. For example, Οβ is discontinuous if kβ β 0
and the bushing has a large rotation so qβ jumps from β βΟ to Ο
. Ο can also be discontinuous if one of qΜβ, qΜβ, qΜβ is discontinuous and its associated torque damper constant is nonzero. For example, Οβ is discontinuous if dβ β 0
and qΜβ is undefined (which occurs when pitch = qβ = Ο/2
). Note: Due to the relationship of π to Ο shown below, π is discontinuous if Ο is discontinuous.
As shown below, there are multiple ways to estimate torque and force stiffness and damping constants. Use a method or combination of methods appropriate for your application. For example, some methods are more useful for a real physical bushing whereas other methods (called "penalty methods") can be more useful when replacing an ideal joint (such as a revolute or fixed/weld joint) with a bushing.
Consider a penalty method if you want a bushing to substitute for a "hard" constraint (e.g., an ideal joint). Since a bushing is inherently compliant it will violate a hard constraint somewhat. The stiffer the bushing, the more accurately it enforces the hard constraint, but at a cost of more computational time. To balance accuracy versus time, consider your tolerance for constraint errors. For example, is it OK for your bushing to displace xβββ = 1 mm for an estimated Fxβββ = 100 N? Also, one way to choose a force damping constant dx is by choosing a "reasonably small" settling time tβ, where settling time tβ is the interval of time for a system to settle to within 1% (0.01) of an equilibrium solution). Is tβ = 0.01 s negligible for a robot arm with a 10 s reach maneuver?
The estimate of stiffness kβ depends on whether you are modeling a physical bushing (consider stiffness methods 1 or 2 below) or whether you are using a bushing to replace an ideal joint such as a revolute or fixed/weld joint (consider stiffness "penalty methods" 3 or 4 below).
kβ = Mxβββ / qβββ
(units of N*m/rad).kβ = Iβ ΟβΒ²
(units of N*m/rad).The estimate of damping dβ depends on whether you are modeling a physical bushing (consider damping method 1 below) or whether you are using a bushing to enforce a constraint (consider damping methods 2 or 3 below).
dβ = 2 ΞΆ kβ / Οβ
(units of N*m*s/rad).dβ = 2 ΞΆ kβ / Οβ
(units of N*m*s/rad).dβ = 2 ΞΆ β(Iβ kβ)
.Refer to Advanced bushing stiffness and damping for more details.
The estimate of stiffness kx depends on whether you are modeling a real bushing (consider stiffness methods 1 or 2 below) or whether you are using a bushing to replace an ideal joint such as a revolute or fixed/weld joint (consider stiffness "penalty methods" 3 or 4 below).
kx = Fxβββ / xβββ
(units of N/m).kx = m ΟβΒ²
(units of N/m).The estimate of damping dx depends on whether you are modeling a physical bushing (consider damping method 1 below) or whether you are using a bushing to enforce a constraint (consider damping methods 2 or 3 below).
dx = 2 ΞΆ kx / Οβ
(units of N*s/m).dx = 2 ΞΆ kx / Οβ
(units of N*s/m).dx = 2 ΞΆ β(m kx)
(units of N*s/m).Refer to Advanced bushing stiffness and damping for more details.
To understand how "gimbal torques" Ο relate to π, it helps to remember that the RollPitchYaw class documentation states that a Space-fixed (extrinsic) X-Y-Z rotation with roll-pitch-yaw angles [qβ qβ qβ] is equivalent to a Body-fixed (intrinsic) Z-Y-X rotation by yaw-pitch-roll angles [qβ qβ qβ]. In the context of "gimbal torques", the Body-fixed Z-Y-X rotation sequence with angles [qβ qβ qβ] is physical meaningful as it produces torques associated with successive frames in a gimbal as Οβ ππ³, Οβ ππ², Οβ ππ±, where each of ππ³, ππ², ππ± are unit vectors associated with a frame in the yaw-pitch-roll rotation sequence and ππ² is a unit vector of the "pitch" intermediate frame. As described earlier, torque π is the moment of the bushing forces on frame C about Cp. Scalars tx, ty, tz are defined so π can be expressed π = [tx ty tz]α΄ = tx ππ± + ty ππ² + tz ππ³
. As shown in code documentation, the relationship of [tx ty tz] to [Οβ Οβ Οβ] was found by equating π's power to Ο's power as π β
w_AC = Ο β
qΜ.
β tx β β Οβ β β cos(qβ)/cos(qβ) sin(qβ)/cos(qβ) 0 β | ty | = Nα΅ | Οβ | where N = | βsin(q2) cos(q2) 0 | β tz β β Οβ β β cos(qβ)*tan(qβ) sin(qβ)*tan(qβ) 1 β
The basics on how to choose bushing stiffness and damping constants are at:
The list below provides more detail on: The performance tradeoff between high stiffness and long simulation time; loads that affect estimates of Mxβββ or Fxβββ; and how a linear 2βΏα΅-order ODE provides insight on how to experimentally determine stiffness and damping constants.
m xΜ + dx xΜ + kx x = 0 or alternatively as xΜ + 2 ΞΆ Οβ xΜ + ΟβΒ² x = 0 where ΟβΒ² = kx/m, ΞΆ = dx / (2 β(m kx))Οβ and ΞΆ also appear in the related ODEs for rotational systems, namely
Iβ qΜ + dβ qΜ + kβ q = 0 or alternatively as qΜ + 2 ΞΆ Οβ qΜ + ΟβΒ² q = 0 where ΟβΒ² = kβ/Iβ, ΞΆ = dβ / (2 β(Iβ kβ))One way to determine Οβ is from settling time tβ which approximates the time for a system to settle to within a specified settling ratio of an equilibrium solutions. Typical values for settling ratio are 1% (0.01), 2% (0.02), 5% (0.05), and 10% (0.10).
Settling ratio | Οβ |
---|---|
0.01 | 6.64 / tβ |
0.02 | 5.83 / tβ |
0.05 | 4.74 / tβ |
0.10 | 3.89 / tβ |
Since a literature reference for this formula was not found, the derivation below was done at TRI (it has not been peer reviewed). This formula results from the "dominant pole" solution in the prototypical constant-coefficient linear 2βΏα΅-order ODE. For xΜ(0) = 0, mathematics shows poles pβ = -Οβ sβ, pβ = -Οβ sβ, where sz = β(ΞΆΒ² - 1), sβ = ΞΆ - sz, sβ = ΞΆ + sz. and
x(t) / x(0) = pβ/(pβ-pβ) exp(pβ t) - pβ/(pβ-pβ) exp(pβ t) = sβ/(sβ-sβ) exp(pβ t) - sβ/(sβ-sβ) exp(pβ t) = k/( k-1 ) exp(pβ t) - 1/( k-1 ) exp(pβ t) where k = sβ / sβ β k/( k-1 ) exp(pβ t) since pβ > pβ
Note: k = sβ / sβ is real, k > 0, sβ = k sβ, and pβ > pβ (pβ is less negative then pβ), so exp(pβ t) decays to zero slower than exp(pβ t) and exp(pβ t) β« exp(pβ t) for sufficiently large t. Hence we assume exp(pβ t) β 0 (which is why pβ is called the "dominant pole"). Next,
k/(k - 1) = sβ / sβ / (sβ/sβ -1) = sβ / (sβ - sβ) = sβ / (2 sz), so x(t) / x(0) β sβ / (2 sz) exp(-sβ Οβ t), hence settling_ratio β sβ / (2 sz) exp(-sβ Οβ tβ), finally Οβ β -ln(settling_ratio 2 sz / sβ) / (sβ tβ)
The table below shows that there is little error in this approximate formula for various settling ratios and ΞΆ, particularly for ΞΆ β₯ 1.1. For 1.0 β€ ΞΆ < 1.1, the critical damping estimates of Οβ work well.
Settling ratio | ΞΆ = 1.01 | ΞΆ = 1.1 | ΞΆ = 1.2 | ΞΆ = 1.3 | ΞΆ = 1.5 |
---|---|---|---|---|---|
0.01 | 1.98% | 0.005% | 2.9E-5% | 1.6E-7% | 2.4E-12% |
0.02 | 2.91% | 0.016% | 1.8E-4% | 2.1E-6% | 1.6E-10% |
0.05 | 5.10% | 0.076% | 2.3E-3% | 7.0E-5% | 4.4E-8% |
0.10 | 8.28% | 0.258% | 1.6E-2% | 1.0E-3% | 3.3E-6% |
Note: There is a related derivation in the reference below, however, it needlessly makes the oversimplified approximation k/(k - 1) β 1. https://electronics.stackexchange.com/questions/296567/over-and-critically-damped-systems-settling-time
T | The underlying scalar type. Must be a valid Eigen scalar. |
[qβ qβ qβ]
.#include <drake/multibody/tree/linear_bushing_roll_pitch_yaw.h>
Public Member Functions | |
LinearBushingRollPitchYaw (const Frame< T > &frameA, const Frame< T > &frameC, const Vector3< double > &torque_stiffness_constants, const Vector3< double > &torque_damping_constants, const Vector3< double > &force_stiffness_constants, const Vector3< double > &force_damping_constants) | |
Construct a LinearBushingRollPitchYaw B that connects frames A and C, where frame A is welded to a link L0 and frame C is welded to a link L1. More... | |
~LinearBushingRollPitchYaw () override | |
const RigidBody< T > & | link0 () const |
Returns link (body) L0 (frame A is welded to link L0). More... | |
const RigidBody< T > & | link1 () const |
Returns link (body) L1 (frame C is welded to link L1). More... | |
const Frame< T > & | frameA () const |
Returns frame A, which is the frame that is welded to link (body) L0 and attached to the bushing. More... | |
const Frame< T > & | frameC () const |
Returns frame C, which is the frame that is welded to link (body) L1 and attached to the bushing. More... | |
const Vector3< double > & | torque_stiffness_constants () const |
Returns the default torque stiffness constants [kβ kβ kβ] (units of N*m/rad). More... | |
const Vector3< double > & | torque_damping_constants () const |
Returns the default torque damping constants [dβ dβ dβ] (units of N*m*s/rad). More... | |
const Vector3< double > & | force_stiffness_constants () const |
Returns the default force stiffness constants [kx ky kz] (units of N/m). More... | |
const Vector3< double > & | force_damping_constants () const |
Returns the default force damping constants [dx dy dz] (units of N*s/m). More... | |
SpatialForce< T > | CalcBushingSpatialForceOnFrameA (const systems::Context< T > &context) const |
Calculate F_A_A, the bushing's spatial force on frame A expressed in A. More... | |
SpatialForce< T > | CalcBushingSpatialForceOnFrameC (const systems::Context< T > &context) const |
Calculate F_C_C, the bushing's spatial force on frame C expressed in C. More... | |
Does not allow copy, move, or assignment | |
LinearBushingRollPitchYaw (const LinearBushingRollPitchYaw &)=delete | |
LinearBushingRollPitchYaw & | operator= (const LinearBushingRollPitchYaw &)=delete |
LinearBushingRollPitchYaw (LinearBushingRollPitchYaw &&)=delete | |
LinearBushingRollPitchYaw & | operator= (LinearBushingRollPitchYaw &&)=delete |
Vector3< T > | GetTorqueStiffnessConstants (const systems::Context< T > &context) const |
Returns the torque stiffness constants [kβ kβ kβ] (units of N*m/rad) stored in context . More... | |
Vector3< T > | GetTorqueDampingConstants (const systems::Context< T > &context) const |
Returns the torque damping constants [dβ dβ dβ] (units of N*m*s/rad) stored in context . More... | |
Vector3< T > | GetForceStiffnessConstants (const systems::Context< T > &context) const |
Returns the force stiffness constants [kx ky kz] (units of N/m) stored in context . More... | |
Vector3< T > | GetForceDampingConstants (const systems::Context< T > &context) const |
Returns the force damping constants [dx dy dz] (units of N*s/m) stored in context . More... | |
void | SetTorqueStiffnessConstants (systems::Context< T > *context, const Vector3< T > &torque_stiffness) const |
Sets the torque stiffness constants [kβ kβ kβ] (units of N*m/rad) in context . More... | |
void | SetTorqueDampingConstants (systems::Context< T > *context, const Vector3< T > &torque_damping) const |
Sets the torque damping constants [dβ dβ dβ] (units of N*m*s/rad) in context . More... | |
void | SetForceStiffnessConstants (systems::Context< T > *context, const Vector3< T > &force_stiffness) const |
Sets the force stiffness constants [kx ky kz] (units of N/m) in context . More... | |
void | SetForceDampingConstants (systems::Context< T > *context, const Vector3< T > &force_damping) const |
Sets the force damping constants [dx dy dz] (units of N*s/m) in context . 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 |
Friends | |
class | BushingTester |
template<typename U > | |
class | LinearBushingRollPitchYaw |
Additional Inherited Members | |
Methods to make a clone templated on different scalar types. | |
Specific force element subclasses must implement these to support scalar conversion to other types. These methods are only called from MultibodyTree::CloneToScalar(); users must not call these explicitly since there is no external mechanism to ensure the argument template <typename T> public: // Class's constructor. SpringElement( const RigidBody<T>& body1, const RigidBody<T>& body2, double stiffness); // Get the first body to which this spring is connected. const RigidBody<T>& get_body1() const; // Get the second body to which this spring is connected. const RigidBody<T>& get_body2() const; // Get the spring stiffness constant. double get_stiffness() const; protected: // Implementation of the scalar conversion from T to double. std::unique_ptr<ForceElement<double>> DoCloneToScalar( const MultibodyTree<double>& tree_clone) const) { const RigidBody<ToScalar>& body1_clone = tree_clone.get_variant(get_body1()); const RigidBody<ToScalar>& body2_clone = tree_clone.get_variant(get_body2()); return std::make_unique<SpringElement<double>>( body1_clone, body2_clone, get_stiffness()); } MultibodyTree::get_variant() methods are available to retrieve cloned variants from For examples on how a MultibodyTree model can be converted to other scalar types, please refer to the documentation for MultibodyTree::CloneToScalar(). | |
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... | |
|
delete |
|
delete |
LinearBushingRollPitchYaw | ( | const Frame< T > & | frameA, |
const Frame< T > & | frameC, | ||
const Vector3< double > & | torque_stiffness_constants, | ||
const Vector3< double > & | torque_damping_constants, | ||
const Vector3< double > & | force_stiffness_constants, | ||
const Vector3< double > & | force_damping_constants | ||
) |
Construct a LinearBushingRollPitchYaw B that connects frames A and C, where frame A is welded to a link L0 and frame C is welded to a link L1.
[in] | frameA | frame A of link (body) L0 that connects to bushing B. |
[in] | frameC | frame C of link (body) L1 that connects to bushing B. |
[in] | torque_stiffness_constants | [kβ kβ kβ] multiply the roll-pitch-yaw angles [qβ qβ qβ] to produce the spring portion of the "gimbal" torques Οβ, Οβ, Οβ. The SI units of kβ, kβ, kβ are N*m/rad. |
[in] | torque_damping_constants | [dβ dβ dβ] multiply the roll-pitch-yaw rates [qΜβ qΜβ qΜβ] to produce the damper portion of the "gimbal" torques Οβ, Οβ, Οβ. The SI units of dβ, dβ, dβ are N*m*s/rad. |
[in] | force_stiffness_constants | [kx ky kz] multiply the bushing displacements [x y z] to form πα΄, the spring portion of the force π = [fx fy fz]Κ. The SI units of kx, ky, kz are N/m. |
[in] | force_damping_constants | [dx dy dz] multiply the bushing displacement rates [xΜ yΜ zΜ] to form πα΄
, the damper portion of the force π = [fx fy fz]Κ. The SI units of dx, dy, dz are N*s/m. |
|
override |
SpatialForce<T> CalcBushingSpatialForceOnFrameA | ( | const systems::Context< T > & | context | ) | const |
Calculate F_A_A, the bushing's spatial force on frame A expressed in A.
F_A_A contains two vectors: the moment of all bushing forces on A about Ao (βπ + p_AoAp Γ βπ) and the net bushing force on A (βπ expressed in A).
[in] | context | The state of the multibody system. |
std::exception | if pitch angle is near gimbal-lock. For more info, |
SpatialForce<T> CalcBushingSpatialForceOnFrameC | ( | const systems::Context< T > & | context | ) | const |
Calculate F_C_C, the bushing's spatial force on frame C expressed in C.
F_C_C contains two vectors: the moment of all bushing forces on C about Co (π + p_CoCp Γ π) and the resultant bushing force on C (π expressed in C).
[in] | context | The state of the multibody system. |
std::exception | if pitch angle is near gimbal-lock. For more info, |
Returns the default force damping constants [dx dy dz]
(units of N*s/m).
Refer to How to choose force stiffness and damping constants for more details.
Returns the default force stiffness constants [kx ky kz]
(units of N/m).
Refer to How to choose force stiffness and damping constants for more details.
const Frame<T>& frameA | ( | ) | const |
Returns frame A, which is the frame that is welded to link (body) L0 and attached to the bushing.
const Frame<T>& frameC | ( | ) | const |
Returns frame C, which is the frame that is welded to link (body) L1 and attached to the bushing.
Vector3<T> GetForceDampingConstants | ( | const systems::Context< T > & | context | ) | const |
Returns the force damping constants [dx dy dz]
(units of N*s/m) stored in context
.
Vector3<T> GetForceStiffnessConstants | ( | const systems::Context< T > & | context | ) | const |
Returns the force stiffness constants [kx ky kz]
(units of N/m) stored in context
.
Vector3<T> GetTorqueDampingConstants | ( | const systems::Context< T > & | context | ) | const |
Returns the torque damping constants [dβ dβ dβ]
(units of N*m*s/rad) stored in context
.
Vector3<T> GetTorqueStiffnessConstants | ( | const systems::Context< T > & | context | ) | const |
Returns the torque stiffness constants [kβ kβ kβ]
(units of N*m/rad) stored in context
.
The following set of methods allow for access and modification of torque/force stiffness/damping parameters stored in a systems::Context. Refer to How to choose force stiffness and damping constants for more details.
const RigidBody<T>& link0 | ( | ) | const |
Returns link (body) L0 (frame A is welded to link L0).
const RigidBody<T>& link1 | ( | ) | const |
Returns link (body) L1 (frame C is welded to link L1).
|
delete |
|
delete |
void SetForceDampingConstants | ( | systems::Context< T > * | context, |
const Vector3< T > & | force_damping | ||
) | const |
Sets the force damping constants [dx dy dz]
(units of N*s/m) in context
.
void SetForceStiffnessConstants | ( | systems::Context< T > * | context, |
const Vector3< T > & | force_stiffness | ||
) | const |
Sets the force stiffness constants [kx ky kz]
(units of N/m) in context
.
void SetTorqueDampingConstants | ( | systems::Context< T > * | context, |
const Vector3< T > & | torque_damping | ||
) | const |
Sets the torque damping constants [dβ dβ dβ]
(units of N*m*s/rad) in context
.
void SetTorqueStiffnessConstants | ( | systems::Context< T > * | context, |
const Vector3< T > & | torque_stiffness | ||
) | const |
Sets the torque stiffness constants [kβ kβ kβ]
(units of N*m/rad) in context
.
Returns the default torque damping constants [dβ dβ dβ]
(units of N*m*s/rad).
Refer to How to choose torque stiffness and damping constants for more details.
Returns the default torque stiffness constants [kβ kβ kβ]
(units of N*m/rad).
Refer to How to choose torque stiffness and damping constants for more details.
|
friend |
|
friend |