Simbody
3.5
|
This force element represents a bushing acting to connect a frame F fixed on one body (B1) to a frame M fixed on a second body (B2), by a massless, compliant element with linear stiffness and damping properties. More...
Public Member Functions | |
LinearBushing (GeneralForceSubsystem &forces, const MobilizedBody &body1, const Transform &frameFOnB1, const MobilizedBody &body2, const Transform &frameMOnB2, const Vec6 &stiffness, const Vec6 &damping) | |
Create a LinearBushing between a pair of arbitrary frames, one fixed to each of two bodies. More... | |
LinearBushing (GeneralForceSubsystem &forces, const MobilizedBody &body1, const MobilizedBody &body2, const Vec6 &stiffness, const Vec6 &damping) | |
Create a LinearBushing connecting the body frames of two bodies. More... | |
LinearBushing () | |
Default constructor creates an empty handle. More... | |
Default Parameters | |
These refer to Topology-stage parameters normally set in the constructor; these determine the initial values assigned to the corresponding Instance-stage state variables.
| |
LinearBushing & | setDefaultFrameOnBody1 (const Transform &X_B1F) |
Set the frame F on body B1 that will be used by default as one of the frames connected by the bushing, by giving the transform X_B1F locating frame F with respect to the body frame B1. More... | |
LinearBushing & | setDefaultFrameOnBody2 (const Transform &X_B2M) |
Set the frame M on body B2 that will be used by default as one of the frames connected by the bushing, by giving the transform X_B2M locating frame M with respect to the body frame B2. More... | |
LinearBushing & | setDefaultStiffness (const Vec6 &stiffness) |
Set the stiffnesses (spring constants) k that will be used by default for this Bushing; these must be nonnegative. More... | |
LinearBushing & | setDefaultDamping (const Vec6 &damping) |
Set the damping coefficients c that will be used by default for this Bushing; these must be nonnegative. More... | |
const Transform & | getDefaultFrameOnBody1 () const |
Return the frame F on body B1 that will be used by default as one of the frames connected by the bushing, as the transform X_B1F locating frame F with respect to the body frame B1. More... | |
const Transform & | getDefaultFrameOnBody2 () const |
Return the frame M on body B2 that will be used by default as one of the frames connected by the bushing, as the transform X_B2M locating frame M with respect to the body frame B2. More... | |
const Vec6 & | getDefaultStiffness () const |
Return the stiffnesses k that will be used by default for this Bushing. More... | |
const Vec6 & | getDefaultDamping () const |
Return the damping coefficients c that will be used by default for this Bushing. More... | |
Instance Parameters | |
These refer to the Instance-stage state variables that determine the geometry and material properties that will be used in computations involving this Bushing when performed with the given State. If these are not set explicitly, the default values are set to those provided in the constructor or via the correponding setDefault...() methods.
| |
const LinearBushing & | setFrameOnBody1 (State &state, const Transform &X_B1F) const |
Set the frame F on body B1 that will be used as one of the frames connected by the bushing when evaluating with this State, by giving the transform X_B1F locating frame F with respect to the body frame B1. More... | |
const LinearBushing & | setFrameOnBody2 (State &state, const Transform &X_B2M) const |
Set the frame M on body B2 that will be used as one of the frames connected by the bushing when evaluating with this State, by giving the transform X_B2M locating frame M with respect to the body frame B2. More... | |
const LinearBushing & | setStiffness (State &state, const Vec6 &stiffness) const |
Set the stiffnesses (spring constants) k that will be used for this Bushing when evaluated using this State. More... | |
const LinearBushing & | setDamping (State &state, const Vec6 &damping) const |
Set the damping coefficients c that will be used for this Bushing when evaluated using this State. More... | |
const Transform & | getFrameOnBody1 (const State &state) const |
Return the frame F on body B1 currently being used by this State as one of the frames connected by the bushing, as the transform X_B1F locating frame F with respect to the body frame B1. More... | |
const Transform & | getFrameOnBody2 (const State &state) const |
Return the frame M on body B2 currently being used by this State as one of the frames connected by the bushing, as the transform X_B2M locating frame M with respect to the body frame B2. More... | |
const Vec6 & | getStiffness (const State &state) const |
Return the stiffnesses (spring constants) k currently being used for this Bushing by this State. More... | |
const Vec6 & | getDamping (const State &state) const |
Return the damping coefficients c currently being used for this Bushing by this State. More... | |
Position-related Quantities | |
These methods return position-dependent quantities that are calculated by the Bushing as part of its force calculations and stored in the State cache. These can be obtained at no cost, although the first call after a position change may initiate computation if forces haven't already been computed.
| |
const Vec6 & | getQ (const State &state) const |
Obtain the generalized coordinates last calculated by this force element. More... | |
const Transform & | getX_GF (const State &state) const |
Obtain the spatial transform X_GF giving the location and orientation of body 1's frame F in Ground. More... | |
const Transform & | getX_GM (const State &state) const |
Obtain the spatial transform X_GM giving the location and orientation of body 2's frame M in Ground. More... | |
const Transform & | getX_FM (const State &state) const |
Obtain the spatial transform X_FM giving the location and orientation of body 2's frame M in body 1's frame F. More... | |
Velocity-related Quantities | |
These methods return velocity-dependent quantities that are calculated by the Bushing as part of its force calculations and stored in the State cache. These can be obtained at no cost, although the first call after a velocity change may initiate computation if forces haven't already been computed.
| |
const Vec6 & | getQDot (const State &state) const |
Obtain the generalized coordinate derivatives last calculated by this force element. More... | |
const SpatialVec & | getV_GF (const State &state) const |
Obtain the spatial velocity V_GF giving the velocity of body 1's frame F in the Ground frame. More... | |
const SpatialVec & | getV_GM (const State &state) const |
Obtain the spatial velocity V_GM giving the velocity of body 2's frame M in the Ground frame. More... | |
const SpatialVec & | getV_FM (const State &state) const |
Obtain the spatial velocity V_FM giving the velocity of body 2's frame M in body 1's frame F, expressed in the F frame. More... | |
Forces | |
These methods return the forces being applied by this Bushing in the configuration and velocities contained in the supplied State. These are evaluated during force calculation and available at no computational cost afterwards, although the first call after a velocity change may initiate computation if forces haven't already been computed.
| |
const Vec6 & | getF (const State &state) const |
Obtain the generalized forces f being applied by this Bushing force element on each of its six axes. More... | |
const SpatialVec & | getF_GM (const State &state) const |
Return the spatial force F_GM being applied by this Bushing to body 2 at its M frame, expressed in the Ground frame. More... | |
const SpatialVec & | getF_GF (const State &state) const |
Return the spatial force F_GF being applied by this Bushing to body 1 at its F frame, expressed in the Ground frame. More... | |
Energy, Power, and Work | |
These methods return the energy, power, and work-related quantities associated with this Bushing element for the values in the supplied State. | |
Real | getPotentialEnergy (const State &state) const |
Obtain the potential energy stored in this Bushing in the current configuration. More... | |
Real | getPowerDissipation (const State &state) const |
Obtain the rate at which energy is being dissipated by this Bushing, that is, the power being lost. More... | |
Real | getDissipatedEnergy (const State &state) const |
Obtain the total amount of energy dissipated by this Bushing since some arbitrary starting point. More... | |
void | setDissipatedEnergy (State &state, Real energy) const |
Set the accumulated dissipated energy to an arbitrary value. More... | |
Public Member Functions inherited from SimTK::Force | |
void | disable (State &) const |
Disable this force element, effectively removing it from the System for computational purposes (it is still using its ForceIndex, however). More... | |
void | enable (State &) const |
Enable this force element if it was previously disabled. More... | |
bool | isDisabled (const State &) const |
Test whether this force element is currently disabled in the supplied State. More... | |
void | setDisabledByDefault (bool shouldBeDisabled) |
Normally force elements are enabled when defined and can be disabled later. More... | |
bool | isDisabledByDefault () const |
Test whether this force element is disabled by default in which case it must be explicitly enabled before it will take effect. More... | |
void | calcForceContribution (const State &state, Vector_< SpatialVec > &bodyForces, Vector_< Vec3 > &particleForces, Vector &mobilityForces) const |
Calculate the force that would be applied by this force element if the given state were realized to Dynamics stage. More... | |
Real | calcPotentialEnergyContribution (const State &state) const |
Calculate the potential energy contribution that is made by this force element at the given state. More... | |
Force () | |
Default constructor for Force handle base class does nothing. More... | |
operator ForceIndex () const | |
Implicit conversion to ForceIndex when needed. More... | |
const GeneralForceSubsystem & | getForceSubsystem () const |
Get the GeneralForceSubsystem of which this Force is an element. More... | |
ForceIndex | getForceIndex () const |
Get the index of this force element within its parent force subsystem. More... | |
Public Member Functions inherited from SimTK::PIMPLHandle< Force, ForceImpl, true > | |
bool | isEmptyHandle () const |
Returns true if this handle is empty, that is, does not refer to any implementation object. More... | |
bool | isOwnerHandle () const |
Returns true if this handle is the owner of the implementation object to which it refers. More... | |
bool | isSameHandle (const Force &other) const |
Determine whether the supplied handle is the same object as "this" PIMPLHandle. More... | |
void | disown (Force &newOwner) |
Give up ownership of the implementation to an empty handle. More... | |
PIMPLHandle & | referenceAssign (const Force &source) |
"Copy" assignment but with shallow (pointer) semantics. More... | |
PIMPLHandle & | copyAssign (const Force &source) |
This is real copy assignment, with ordinary C++ object ("value") semantics. More... | |
void | clearHandle () |
Make this an empty handle, deleting the implementation object if this handle is the owner of it. More... | |
const ForceImpl & | getImpl () const |
Get a const reference to the implementation associated with this Handle. More... | |
ForceImpl & | updImpl () |
Get a writable reference to the implementation associated with this Handle. More... | |
int | getImplHandleCount () const |
Return the number of handles the implementation believes are referencing it. More... | |
Additional Inherited Members | |
Public Types inherited from SimTK::PIMPLHandle< Force, ForceImpl, true > | |
typedef PIMPLHandle< Force, ForceImpl, PTR > | HandleBase |
typedef HandleBase | ParentHandle |
Protected Member Functions inherited from SimTK::Force | |
Force (ForceImpl *r) | |
Use this in a derived Force handle class constructor to supply the concrete implementation object to be stored in the handle base. More... | |
Protected Member Functions inherited from SimTK::PIMPLHandle< Force, ForceImpl, true > | |
PIMPLHandle () | |
The default constructor makes this an empty handle. More... | |
PIMPLHandle (ForceImpl *p) | |
This provides consruction of a handle referencing an existing implementation object. More... | |
PIMPLHandle (const PIMPLHandle &source) | |
The copy constructor makes either a deep (value) or shallow (reference) copy of the supplied source PIMPL object, based on whether this is a "pointer
semantics" (PTR=true) or "object (value) semantics" (PTR=false, default) class. More... | |
~PIMPLHandle () | |
Note that the destructor is non-virtual. More... | |
PIMPLHandle & | operator= (const PIMPLHandle &source) |
Copy assignment makes the current handle either a deep (value) or shallow (reference) copy of the supplied source PIMPL object, based on whether this is a "pointer sematics" (PTR=true) or "object (value) semantics" (PTR=false, default) class. More... | |
void | setImpl (ForceImpl *p) |
Set the implementation for this empty handle. More... | |
bool | hasSameImplementation (const Force &other) const |
Determine whether the supplied handle is a reference to the same implementation object as is referenced by "this" PIMPLHandle. More... | |
This force element represents a bushing acting to connect a frame F fixed on one body (B1) to a frame M fixed on a second body (B2), by a massless, compliant element with linear stiffness and damping properties.
The relative orientation R_FM of frame M given in frame F is parametrized by an x-y-z (1-2-3) B2-fixed Euler angle sequence and their time derivatives, as well as a position vector p_FM from F's origin OF to M's origin OM expressed in F, and its time derivative (velocity) v_FM (taken in F). For small orientation displacements, the Euler angles can be considered independent rotations about x, y, and z. Stiffness and damping parameters (6 of each) are provided for each direction's rotation and translation. The 6 coordinates q are defined as the three Euler angles [qx,qy,qz] followed by the three translations [px,py,pz]=p_FM.
This force element is intended for small-displacement use, but is defined nonlinearly so is physically correct for large displacements also. However, be aware that the inferred q's cannot "wrap" so you must keep the motion small enough that the set of q's inferred from the transform X_FM (M's configuration in F) is continuous during a simulation. Also, the Bushing is singular in a configuration in which the middle rotation angle is near 90 degrees, because the time derivative of that angle is unbounded; you should stay far away from that configuration.
If you would like a force element like this one but suited for very large rotations (e.g., multiple revolutions along one of the axes) you should arrange to have a Bushing Mobilizer connected between frames F and M so that you can apply mobility forces rather than body forces as we're doing here. In that case the q's are the defining coordinates rather than the frames, and mobilizer Euler angle q's can wrap continuously without limit. However, with Euler angles there is necessarily a singular configuration so one of the axes must be kept within a modest range even if you use mobilizer coordinates.
The LinearBushing calculates the relative orientation X_FM between the frames, and the relative spatial velocity V_FM. From these it infers a set of q's and qdot's as though there were a gimbal-like mechanism connecting frame F to frame M. This is done using standard formulas to decompose a rotation matrix into an Euler sequence (1-2-3 body fixed in this case) and to convert angular velocity to the time derivatives of the Euler angles. (There are also translational q's but they are trivial.)
The generated force is then calculated for each of the 6 inferred coordinates and their 6 time derivatives as
f_i = -(k_i*q_i + c_i*qdot_i).
Each contribution to potential energy is
e_i = k_i*q_i^2/2.
The damping terms contribute no potential energy, but dissipate power at a rate
p_i = c_i*qdot_i^2.
Numerically integrating the dissipated power over time gives the energy dissipated by the Bushing since some arbitrary starting time and can be used to check conservation of energy in the presence of damping. The LinearBushing force allocates a state variable for this purpose so tracks the energy it dissipates; see the getDissipatedEnergy() method.
The scalar rotational moments f_0, f_1, and f_2 act about rotated axes so do not constitute a vector; they are transformed internally here to produce the appropriate moments on the bodies. The scalar translational forces f_3, f_4, f_5 on the other hand are aligned with frame F's axes so constitute a vector in F.
SimTK::Force::LinearBushing::LinearBushing | ( | GeneralForceSubsystem & | forces, |
const MobilizedBody & | body1, | ||
const Transform & | frameFOnB1, | ||
const MobilizedBody & | body2, | ||
const Transform & | frameMOnB2, | ||
const Vec6 & | stiffness, | ||
const Vec6 & | damping | ||
) |
Create a LinearBushing between a pair of arbitrary frames, one fixed to each of two bodies.
[in,out] | forces | The subsystem to which this force should be added. |
[in] | body1 | The first body to which the force should be applied. |
[in] | frameFOnB1 | A frame F fixed to body 1 given by its constant transform X_B1F from the B1 frame. |
[in] | body2 | The other body to which the force should be applied. |
[in] | frameMOnB2 | A frame M fixed to body 2 given by its constant transform X_B2M from the B2 frame. |
[in] | stiffness | The six nonnegative spring constants, torsional followed by translational. |
[in] | damping | The six nonnegative damping coefficients, torsional followed by translational. |
SimTK::Force::LinearBushing::LinearBushing | ( | GeneralForceSubsystem & | forces, |
const MobilizedBody & | body1, | ||
const MobilizedBody & | body2, | ||
const Vec6 & | stiffness, | ||
const Vec6 & | damping | ||
) |
Create a LinearBushing connecting the body frames of two bodies.
This is the same as the more general constructor except it assumes identity transforms for the two frames, meaning they are coincident with the body frames.
[in,out] | forces | The subsystem to which this force should be added. |
[in] | body1 | The first body to which the force should be applied. |
[in] | body2 | The other body to which the force should be applied. |
[in] | stiffness | The six nonnegative spring constants, torsional followed by translational. |
[in] | damping | The six nonnegative damping coefficients, torsional followed by translational. |
|
inline |
Default constructor creates an empty handle.
LinearBushing& SimTK::Force::LinearBushing::setDefaultFrameOnBody1 | ( | const Transform & | X_B1F | ) |
Set the frame F on body B1 that will be used by default as one of the frames connected by the bushing, by giving the transform X_B1F locating frame F with respect to the body frame B1.
[in] | X_B1F | The Transform giving the default placement of the first Bushing frame F in the body 1 frame B1. |
LinearBushing& SimTK::Force::LinearBushing::setDefaultFrameOnBody2 | ( | const Transform & | X_B2M | ) |
Set the frame M on body B2 that will be used by default as one of the frames connected by the bushing, by giving the transform X_B2M locating frame M with respect to the body frame B2.
[in] | X_B2M | The Transform giving the default placement of the second Bushing frame M in the body 2 frame B2. |
LinearBushing& SimTK::Force::LinearBushing::setDefaultStiffness | ( | const Vec6 & | stiffness | ) |
Set the stiffnesses (spring constants) k that will be used by default for this Bushing; these must be nonnegative.
[in] | stiffness | The six nonnegative spring constants, one for each axis in the order qx,qy,qz,px,py,pz (i.e., rotations first). |
LinearBushing& SimTK::Force::LinearBushing::setDefaultDamping | ( | const Vec6 & | damping | ) |
Set the damping coefficients c that will be used by default for this Bushing; these must be nonnegative.
[in] | damping | The six nonnegative damping coefficients, one for each axis in the order qx,qy,qz,px,py,pz (i.e., rotations first). |
const Transform& SimTK::Force::LinearBushing::getDefaultFrameOnBody1 | ( | ) | const |
Return the frame F on body B1 that will be used by default as one of the frames connected by the bushing, as the transform X_B1F locating frame F with respect to the body frame B1.
const Transform& SimTK::Force::LinearBushing::getDefaultFrameOnBody2 | ( | ) | const |
Return the frame M on body B2 that will be used by default as one of the frames connected by the bushing, as the transform X_B2M locating frame M with respect to the body frame B2.
const Vec6& SimTK::Force::LinearBushing::getDefaultStiffness | ( | ) | const |
Return the stiffnesses k that will be used by default for this Bushing.
const Vec6& SimTK::Force::LinearBushing::getDefaultDamping | ( | ) | const |
Return the damping coefficients c that will be used by default for this Bushing.
const LinearBushing& SimTK::Force::LinearBushing::setFrameOnBody1 | ( | State & | state, |
const Transform & | X_B1F | ||
) | const |
Set the frame F on body B1 that will be used as one of the frames connected by the bushing when evaluating with this State, by giving the transform X_B1F locating frame F with respect to the body frame B1.
[in,out] | state | The State object that is modified by this method. |
[in] | X_B1F | The Transform giving the placement of the first Bushing frame F in the body 1 frame B1. |
const LinearBushing& SimTK::Force::LinearBushing::setFrameOnBody2 | ( | State & | state, |
const Transform & | X_B2M | ||
) | const |
Set the frame M on body B2 that will be used as one of the frames connected by the bushing when evaluating with this State, by giving the transform X_B2M locating frame M with respect to the body frame B2.
[in,out] | state | The State object that is modified by this method. |
[in] | X_B2M | The Transform giving the placement of the second Bushing frame M in the body 2 frame B2. |
const LinearBushing& SimTK::Force::LinearBushing::setStiffness | ( | State & | state, |
const Vec6 & | stiffness | ||
) | const |
Set the stiffnesses (spring constants) k that will be used for this Bushing when evaluated using this State.
[in,out] | state | The State object that is modified by this method. |
[in] | stiffness | Six nonnegative spring constants, one for each axis in the order qx,qy,qz,px,py,pz (i.e., rotations first). |
const LinearBushing& SimTK::Force::LinearBushing::setDamping | ( | State & | state, |
const Vec6 & | damping | ||
) | const |
Set the damping coefficients c that will be used for this Bushing when evaluated using this State.
[in,out] | state | The State object that is modified by this method. |
[in] | damping | Six nonnegative damping coefficients, one for each axis in the order qx,qy,qz,px,py,pz (i.e., rotations first). |
Return the frame F on body B1 currently being used by this State as one of the frames connected by the bushing, as the transform X_B1F locating frame F with respect to the body frame B1.
[in] | state | The State object from which we obtain the frame. |
Return the frame M on body B2 currently being used by this State as one of the frames connected by the bushing, as the transform X_B2M locating frame M with respect to the body frame B2.
[in] | state | The State object from which we obtain the frame. |
Return the stiffnesses (spring constants) k currently being used for this Bushing by this State.
[in] | state | The State object from which we obtain the stiffnesses. |
Return the damping coefficients c currently being used for this Bushing by this State.
[in] | state | The State object from which we obtain the damping coefficients. |
Obtain the generalized coordinates last calculated by this force element.
These are the body2-fixed x-y-z Euler angles qx,qy,qz and p_FM=[px,py,pz], the vector from the frame F origin OF to the frame M origin OM, expressed in the F frame. The full generalized coordinate vector is q=[qx,qy,qz,px,py,pz].
[in] | state | The State from whose cache the coordinates are retrieved. |
Obtain the spatial transform X_GF giving the location and orientation of body 1's frame F in Ground.
[in] | state | The State from whose cache the transform is retrieved. |
Obtain the spatial transform X_GM giving the location and orientation of body 2's frame M in Ground.
[in] | state | The State from whose cache the transform is retrieved. |
Obtain the spatial transform X_FM giving the location and orientation of body 2's frame M in body 1's frame F.
[in] | state | The State from whose cache the transform is retrieved. |
Obtain the generalized coordinate derivatives last calculated by this force element.
These are the body2-fixed x-y-z Euler angle derivatives qdotx,qdoty,qdotz and v_FM=[vx,vy,vz], the velocity of point OM in frame F, expressed in F. That is, v_FM = d/dt p_FM with the derivative taken in the F frame. The full generalized coordinate derivative vector qdot=[qdotx,qdoty,qdotz,vx,vy,vz].
[in] | state | The State from whose cache the coordinate derivatives are retrieved. |
const SpatialVec& SimTK::Force::LinearBushing::getV_GF | ( | const State & | state | ) | const |
Obtain the spatial velocity V_GF giving the velocity of body 1's frame F in the Ground frame.
Note that this is the time derivative of X_GF taken in G, that is, the ordinary spatial velocity.
[in] | state | The State from whose cache the velocity is retrieved. |
const SpatialVec& SimTK::Force::LinearBushing::getV_GM | ( | const State & | state | ) | const |
Obtain the spatial velocity V_GM giving the velocity of body 2's frame M in the Ground frame.
Note that this is the time derivative of X_GM taken in G, that is, the ordinary spatial velocity.
[in] | state | The State from whose cache the velocity is retrieved. |
const SpatialVec& SimTK::Force::LinearBushing::getV_FM | ( | const State & | state | ) | const |
Obtain the spatial velocity V_FM giving the velocity of body 2's frame M in body 1's frame F, expressed in the F frame.
Note that this is the time derivative of X_FM taken in F, which means that V_FM is a local relationship between F and M and is not affected by F's motion with respect to Ground.
[in] | state | The State from whose cache the velocity is retrieved. |
Obtain the generalized forces f being applied by this Bushing force element on each of its six axes.
The sign is such that it would be appropriate to apply to a Bushing mobilizer connecting the same two frames; that is, these are the generalized forces acting on the "outboard" body 2; the negative of these forces acts on the "inboard" body 1.
[in] | state | The State from whose cache the forces are retrieved. |
const SpatialVec& SimTK::Force::LinearBushing::getF_GM | ( | const State & | state | ) | const |
Return the spatial force F_GM being applied by this Bushing to body 2 at its M frame, expressed in the Ground frame.
[in] | state | The State from whose cache the force is retrieved. |
const SpatialVec& SimTK::Force::LinearBushing::getF_GF | ( | const State & | state | ) | const |
Return the spatial force F_GF being applied by this Bushing to body 1 at its F frame, expressed in the Ground frame.
This is equal and opposite to the spatial force applied on body 2.
[in] | state | The State from whose cache the force is retrieved. |
Obtain the potential energy stored in this Bushing in the current configuration.
[in] | state | The State from whose cache the potential energy is retrieved. |
Obtain the rate at which energy is being dissipated by this Bushing, that is, the power being lost.
This is in units of energy/time which is watts in MKS.
[in] | state | The State from which to obtain the current value of the power dissipation. |
Obtain the total amount of energy dissipated by this Bushing since some arbitrary starting point.
This is the time integral of the power dissipation. For a system whose only non-conservative forces are Bushings, the sum of potential, kinetic, and dissipated energies should be conserved. This is a State variable so you can obtain its value any time after it is allocated.
[in] | state | The State from which to obtain the current value of the dissipated energy. |
Set the accumulated dissipated energy to an arbitrary value.
Typically this is used only to reset the dissipated energy to zero, but non-zero values can be useful if you are trying to match some existing data or continuing a simulation. This is a State variable so you can set its value any time after it is allocated.
[in,out] | state | The State whose dissipated energy variable for this Bushing is to be modified. |
[in] | energy | The new value for the accumulated dissipated energy (must be a nonnegative scalar). |