Simbody
|
This is the base class for all MobilizedBody classes, which include a body and a particular kind of mobilizer (joint) connecting that body to its parent. More...
#include <MobilizedBody.h>
Classes | |
class | Ball |
Three mobilities -- unrestricted orientation modeled with a quaternion which is never singular. More... | |
class | BendStretch |
Two mobilities: The z axis of the parent's F frame is used for rotation (and that is always aligned with the M frame z axis). More... | |
class | Custom |
The handle class MobilizedBody::Custom (dataless) and its companion class MobilizedBody::Custom::Implementation can be used together to define new MobilizedBody types with arbitrary properties. More... | |
class | Cylinder |
Two mobilities -- rotation and translation along the common z axis of the inboard and outboard mobilizer frames. More... | |
class | Ellipsoid |
Three mobilities -- coordinated rotation and translation along the surface of an ellipsoid fixed to the parent (inboard) body. More... | |
class | Free |
Unrestricted motion for a rigid body (six mobilities). More... | |
class | FreeLine |
Five mobilities, representing unrestricted motion for a body which is inertialess along its own z axis. More... | |
class | FunctionBased |
This is a subclass of MobilizedBody::Custom which uses a set of Function objects to define the behavior of the MobilizedBody. More... | |
class | Gimbal |
Three mobilities -- unrestricted orientation modeled as a 1-2-3 body-fixed Euler angle sequence. More... | |
class | Ground |
This is a special type of "mobilized" body used as a placeholder for Ground in the 0th slot for a MatterSubsystem's mobilized bodies. More... | |
class | LineOrientation |
Two mobilities, representing unrestricted orientation for a body which is inertialess along its own z axis. More... | |
class | Pin |
One mobility -- rotation about the common z axis of the inboard and outboard mobilizer frames. More... | |
class | Planar |
Three mobilities -- z rotation and x,y translation. More... | |
class | Screw |
One mobility -- coordinated rotation and translation along the common z axis of the inboard and outboard mobilizer frames. More... | |
class | Slider |
One mobility -- translation along the common x axis of the inboard and outboard mobilizer frames. More... | |
class | SphericalCoords |
Three mobilities -- body fixed 3-2 (z-y) rotation followed by translation along body z or body x. More... | |
class | Translation |
Three translational mobilities. More... | |
class | Universal |
Two mobilities -- rotation about the x axis, followed by a rotation about the new y axis. More... | |
class | Weld |
Zero mobilities. More... | |
Public Types | |
enum | Direction { Forward = 0, Reverse = 1 } |
Constructors can take an argument of this type to indicate that the mobilizer is being defined in the reverse direction, meaning from child to parent. More... | |
typedef Pin | Torsion |
typedef Slider | Prismatic |
typedef Translation2D | Cartesian2D |
typedef Translation2D | CartesianCoords2D |
typedef Translation | Cartesian |
typedef Translation | CartesianCoords |
typedef BendStretch | PolarCoords |
typedef TorsionStretch | ConicalCoords2D |
typedef Ball | Orientation |
typedef Ball | Spherical |
Public Member Functions | |
MobilizedBody & | setDefaultMotionType (Motion::Level, Motion::Method=Motion::Prescribed) |
The default behavior of this mobilizer will normally be determined by whether you provide a Motion object for it. | |
void | setMotionType (State &, Motion::Level, Motion::Method=Motion::Prescribed) const |
This is an Instance stage setting. | |
bool | isAccelerationAlwaysZero (const State &) const |
bool | isVelocityAlwaysZero (const State &) const |
MobilizedBody () | |
The default constructor initializes the base class so that it contains a null implementation. | |
MobilizedBody (MobilizedBodyImpl *r) | |
Internal use only. | |
State Access - Bodies | |
const Transform & | getBodyTransform (const State &) const |
Extract from the state cache the already-calculated spatial configuration X_GB of body B's body frame, measured with respect to the Ground frame and expressed in the Ground frame. | |
const Rotation & | getBodyRotation (const State &s) const |
Extract from the state cache the already-calculated spatial orientation R_GB of body B's body frame x, y, and z axes expressed in the Ground frame, as the Rotation matrix R_GB. | |
const Vec3 & | getBodyOriginLocation (const State &s) const |
Extract from the state cache the already-calculated spatial location of body B's body frame origin OB, measured from the Ground origin OG and expressed in the Ground frame, as the position vector p_GB (== p_OG_OB). | |
const Transform & | getMobilizerTransform (const State &) const |
At stage Position or higher, return the cross-mobilizer transform X_FM, the body's inboard mobilizer frame M measured and expressed in the parent body's corresponding outboard frame F. | |
const SpatialVec & | getBodyVelocity (const State &) const |
Extract from the state cache the already-calculated spatial velocity V_GB of this body's reference frame B, measured with respect to the Ground frame and expressed in the Ground frame. | |
const Vec3 & | getBodyAngularVelocity (const State &s) const |
Extract from the state cache the already-calculated inertial angular velocity vector w_GB of this body B, measured with respect to the Ground frame and expressed in the Ground frame. | |
const Vec3 & | getBodyOriginVelocity (const State &s) const |
Extract from the state cache the already-calculated inertial linear velocity vector v_GB (more explicitly, v_G_OB) of this body B's origin point OB, measured with respect to the Ground frame and expressed in the Ground frame. | |
const SpatialVec & | getMobilizerVelocity (const State &) const |
At stage Velocity or higher, return the cross-mobilizer velocity V_FM, the relative velocity of this body's "moving" mobilizer frame M in the parent body's corresponding "fixed" frame F, measured and expressed in F. | |
const SpatialVec & | getBodyAcceleration (const State &s) const |
Extract from the state cache the already-calculated spatial acceleration A_GB of this body's reference frame B, measured with respect to the Ground frame and expressed in the Ground frame. | |
const Vec3 & | getBodyAngularAcceleration (const State &s) const |
Extract from the state cache the already-calculated inertial angular acceleration vector b_GB of this body B, measured with respect to the Ground frame and expressed in the Ground frame. | |
const Vec3 & | getBodyOriginAcceleration (const State &s) const |
Extract from the state cache the already-calculated inertial linear acceleration vector a_GB (more explicitly, a_G_OB) of this body B's origin point OB, measured with respect to the Ground frame and expressed in the Ground frame. | |
const SpatialVec & | getMobilizerAcceleration (const State &) const |
TODO: Not implemented yet -- any volunteers? At stage Acceleration, return the cross-mobilizer acceleration A_FM, the relative acceleration of body B's "moving" mobilizer frame M in the parent body's corresponding "fixed" frame F, measured and expressed in F. | |
const MassProperties & | getBodyMassProperties (const State &) const |
Return a reference to this body's mass properties in the State cache. | |
Real | getBodyMass (const State &s) const |
Return the mass of this body. The State must have been realized to Stage::Instance. | |
const Vec3 & | getBodyMassCenterStation (const State &s) const |
Return this body's center of mass station (i.e., the vector fixed in the body, going from body origin to body mass center, expressed in the body frame.) The State must have been realized to Stage::Instance or higher. | |
const Inertia & | getBodyInertiaAboutBodyOrigin (const State &s) const |
Return a reference to this body's inertia matrix in the State cache, taken about the body origin and expressed in the body frame. | |
const Transform & | getInboardFrame (const State &) const |
Return a reference to this mobilizer's frame F fixed on the parent body P, as the fixed Transform from P's body frame to the frame F fixed to P. | |
const Transform & | getOutboardFrame (const State &) const |
Return a reference to this MobilizedBody's mobilizer frame M, as the fixed Transform from this body B's frame to the frame M fixed on B. | |
void | setInboardFrame (State &, const Transform &X_PF) const |
TODO: not implemented yet. | |
void | setOutboardFrame (State &, const Transform &X_BM) const |
TODO: not implemented yet. | |
State Access - Mobilizer generalized coordinates q and speeds u | |
int | getNumQ (const State &) const |
Return the number of generalized coordinates q currently in use by this mobilizer. | |
int | getNumU (const State &) const |
Return the number of generalized speeds u currently in use by this mobilizer. | |
QIndex | getFirstQIndex (const State &) const |
Return the global QIndex of the first q for this mobilizer; all the q's range from getFirstQIndex() to QIndex(getFirstQIndex()+getNumQ()-1). | |
UIndex | getFirstUIndex (const State &) const |
Return the global UIndex of the first u for this mobilizer; all the u's range from getFirstUIndex() to UIndex(getFirstUIndex()+getNumU()-1). | |
Real | getOneQ (const State &, int which) const |
Return one of the generalized coordinates q from this mobilizer's partition of the matter subsystem's full q vector in the State. | |
Real | getOneU (const State &, int which) const |
Return one of the generalized speeds u from this mobilizer's partition of the matter subsystem's full u vector in the State. | |
Vector | getQAsVector (const State &) const |
Return as a Vector of length getNumQ() all the generalized coordinates q currently in use by this mobilizer, from this mobilizer's partion in the matter subsystem's full q vector in the State. | |
Vector | getUAsVector (const State &) const |
Return as a Vector of length getNumU() all the generalized speeds u currently in use by this mobilizer, from this mobilizer's partion in the matter subsystem's full u vector in the State. | |
Real | getOneQDot (const State &, int which) const |
Return one of the generalized coordinate derivatives qdot from this mobilizer's partition of the matter subsystem's full qdot vector in the State cache. | |
Vector | getQDotAsVector (const State &) const |
Return as a Vector of length getNumQ() all the generalized coordinate derivatives qdot currently in use by this mobilizer, from this mobilizer's partion in the matter subsystem's full qdot vector in the State cache. | |
Real | getOneUDot (const State &, int which) const |
Return one of the generalized accelerations udot from this mobilizer's partition of the matter subsystem's full udot vector in the State cache. | |
Real | getOneQDotDot (const State &, int which) const |
Return one of the generalized coordinate second derivatives qdotdot from this mobilizer's partition of the matter subsystem's full qdotdot vector in the State cache. | |
Vector | getUDotAsVector (const State &) const |
Return as a Vector of length getNumU() all the generalized accelerations udot currently in use by this mobilizer, from this mobilizer's partion in the matter subsystem's full udot vector in the State cache. | |
Vector | getQDotDotAsVector (const State &) const |
Return as a Vector of length getNumQ() all the generalized coordinate second derivatives qdotdot currently in use by this mobilizer, from this mobilizer's partion in the matter subsystem's full qdotdot vector in the State cache. | |
Vector | getTauAsVector (const State &) const |
Return the tau forces resulting from known (prescribed) acceleration, corresponding to each of this mobilizer's mobilities, as a Vector of length getNumU(). | |
Real | getOneTau (const State &, MobilizerUIndex which) const |
Return one of the tau forces resulting from known (prescribed) acceleration, corresponding to one of this mobilizer's mobilities as selected here using the which parameter, numbered from zero to getNumU()-1. | |
void | setOneQ (State &, int which, Real v) const |
Set one of the generalized coordinates q to value v , in this mobilizer's partition of the matter subsystem's full q vector in the State. | |
void | setOneU (State &, int which, Real v) const |
Set one of the generalized speeds u to value v , in this mobilizer's partition of the matter subsystem's full u vector in the State. | |
void | setQFromVector (State &s, const Vector &v) const |
Set all of the generalized coordinates q to value v (a Vector of length getNumQ()), in this mobilizer's partition of the matter subsystem's full q vector in the State. | |
void | setUFromVector (State &s, const Vector &v) const |
Set all of the generalized speeds u to value v (a Vector of length getNumU()), in this mobilizer's partition of the matter subsystem's full u vector in the State. | |
void | setQToFitTransform (State &, const Transform &X_FM) const |
Adjust this mobilizer's q's to best approximate the supplied Transform which requests a particular relative orientation and translation between the "fixed" and "moving" frames connected by this mobilizer. | |
void | setQToFitRotation (State &, const Rotation &R_FM) const |
Adjust this mobilizer's q's to best approximate the supplied Rotation matrix which requests a particular relative orientation between the "fixed" and "moving" frames connected by this mobilizer. | |
void | setQToFitTranslation (State &, const Vec3 &p_FM) const |
Adjust this mobilizer's q's to best approximate the supplied position vector which requests a particular offset between the origins of the "fixed" and "moving" frames connected by this mobilizer, with any q's (rotational or translational) being modified if doing so helps satisfy the request. | |
void | setUToFitVelocity (State &, const SpatialVec &V_FM) const |
Adjust this mobilizer's u's (generalized speeds) to best approximate the supplied spatial velocity V_FM which requests the relative angular and linear velocity between the "fixed" and "moving" frames connected by this mobilizer. | |
void | setUToFitAngularVelocity (State &, const Vec3 &w_FM) const |
Adjust this mobilizer's u's (generalized speeds) to best approximate the supplied angular velocity w_FM which requests a particular relative angular between the "fixed" and "moving" frames connected by this mobilizer. | |
void | setUToFitLinearVelocity (State &, const Vec3 &v_FM) const |
Adjust any of this mobilizer's u's (generalized speeds) to best approximate the supplied linear velocity v_FM which requests a particular velocity for the "moving" frame M origin in the "fixed" frame F on the parent where these are the frames connected by this mobilizer. | |
SpatialVec | getHCol (const State &s, MobilizerUIndex ux) const |
Expert use only: obtain a column of the hinge matrix H corresponding to one of this mobilizer's mobilities (actually a column of H_PB_G; what Jain calls H* and Schwieters calls H^T). | |
SpatialVec | getH_FMCol (const State &s, MobilizerUIndex ux) const |
Expert use only: obtain a column of the mobilizer-local hinge matrix H_FM which maps generalized speeds u to cross-mobilizer spatial velocity V_FM via V_FM=H_FM*u. | |
Basic Operators | |
Transform | findBodyTransformInAnotherBody (const State &s, const MobilizedBody &inBodyA) const |
These methods use state variables and Response methods to compute basic quantities which cannot be precomputed, but which can be implemented with an inline combination of basic floating point operations which can be reliably determined at compile time. | |
Rotation | findBodyRotationInAnotherBody (const State &s, const MobilizedBody &inBodyA) const |
Return R_AB, the rotation matrix giving this body B's axes in body A's frame. | |
Vec3 | findBodyOriginLocationInAnotherBody (const State &s, const MobilizedBody &toBodyA) const |
Return the station on another body A (that is, a point measured and expressed in A) that is currently coincident in space with the origin OB of this body B. | |
SpatialVec | findBodyVelocityInAnotherBody (const State &s, const MobilizedBody &inBodyA) const |
Return the angular and linear velocity of body B's frame in body A's frame, expressed in body A, and arranged as a SpatialVec. | |
Vec3 | findBodyAngularVelocityInAnotherBody (const State &s, const MobilizedBody &inBodyA) const |
Return the angular velocity w_AB of body B's frame in body A's frame, expressed in body A. | |
Vec3 | findBodyOriginVelocityInAnotherBody (const State &s, const MobilizedBody &inBodyA) const |
Return the velocity of body B's origin point in body A's frame, expressed in body A. | |
SpatialVec | findBodyAccelerationInAnotherBody (const State &s, const MobilizedBody &inBodyA) const |
Return the angular and linear acceleration of body B's frame in body A's frame, expressed in body A, and arranged as a SpatialVec. | |
Vec3 | findBodyAngularAccelerationInAnotherBody (const State &s, const MobilizedBody &inBodyA) const |
Return the angular acceleration of body B's frame in body A's frame, expressed in body A. | |
Vec3 | findBodyOriginAccelerationInAnotherBody (const State &s, const MobilizedBody &inBodyA) const |
Return the acceleration of body B's origin point in body A's frame, expressed in body A. | |
Vec3 | findStationLocationInGround (const State &s, const Vec3 &stationOnB) const |
Return the Cartesian (ground) location that is currently coincident with a station (point) S fixed on body B. | |
Vec3 | findStationLocationInAnotherBody (const State &s, const Vec3 &stationOnB, const MobilizedBody &toBodyA) const |
Given a station S on this body B, return the location on another body A which is at the same location in space. | |
Vec3 | findStationVelocityInGround (const State &s, const Vec3 &stationOnB) const |
Given a station fixed on body B, return its inertial (Cartesian) velocity, that is, its velocity relative to the Ground frame, expressed in the Ground frame. | |
Vec3 | findStationVelocityInAnotherBody (const State &s, const Vec3 &stationOnBodyB, const MobilizedBody &inBodyA) const |
Return the velocity of a station S fixed on body B, in body A's frame, expressed in body A. | |
Vec3 | findStationAccelerationInGround (const State &s, const Vec3 &stationOnB) const |
Given a station fixed on body B, return its inertial (Cartesian) acceleration, that is, its acceleration relative to the ground frame, expressed in the ground frame. | |
Vec3 | findStationAccelerationInAnotherBody (const State &s, const Vec3 &stationOnBodyB, const MobilizedBody &inBodyA) const |
Return the acceleration of a station S fixed on body B, in another body A's frame, expressed in body A. | |
void | findStationLocationAndVelocityInGround (const State &s, const Vec3 &locationOnB, Vec3 &locationOnGround, Vec3 &velocityInGround) const |
It is cheaper to calculate a station's ground location and velocity together than to do them separately. | |
void | findStationLocationVelocityAndAccelerationInGround (const State &s, const Vec3 &locationOnB, Vec3 &locationOnGround, Vec3 &velocityInGround, Vec3 &accelerationInGround) const |
It is cheaper to calculate a station's ground location, velocity, and acceleration together than to do them separately. | |
Vec3 | findMassCenterLocationInGround (const State &s) const |
Return the Cartesian (ground) location of this body B's mass center. | |
Vec3 | findMassCenterLocationInAnotherBody (const State &s, const MobilizedBody &toBodyA) const |
Return the point of another body A that is currently coincident in space with the mass center CB of this body B. | |
Vec3 | findStationAtGroundPoint (const State &s, const Vec3 &locationInG) const |
Return the station (point) S of this body B that is coincident with the given Ground location. | |
Vec3 | findStationAtAnotherBodyStation (const State &s, const MobilizedBody &fromBodyA, const Vec3 &stationOnA) const |
Return the station (point) on this body B that is coincident with the given station on another body A. | |
Vec3 | findStationAtAnotherBodyOrigin (const State &s, const MobilizedBody &fromBodyA) const |
Return the station S of this body that is currently coincident in space with the origin OA of another body A. | |
Vec3 | findStationAtAnotherBodyMassCenter (const State &s, const MobilizedBody &fromBodyA) const |
Return the station S of this body that is currently coincident in space with the mass center CA of another body B. | |
Transform | findFrameTransformInGround (const State &s, const Transform &frameOnB) const |
Return the current Ground-frame pose (position and orientation) of a frame F that is fixed to body B. | |
SpatialVec | findFrameVelocityInGround (const State &s, const Transform &frameOnB) const |
Return the current Ground-frame spatial velocity V_GF (that is, angular and linear velocity) of a frame F that is fixed to body B. | |
SpatialVec | findFrameAccelerationInGround (const State &s, const Transform &frameOnB) const |
Return the current Ground-frame spatial acceleration A_GF (that is, angular and linear acceleration) of a frame F that is fixed to body B. | |
Vec3 | expressVectorInGroundFrame (const State &s, const Vec3 &vectorInB) const |
Re-express a vector expressed in this body B's frame into the same vector in G, by applying only a rotation. | |
Vec3 | expressGroundVectorInBodyFrame (const State &s, const Vec3 &vectorInG) const |
Re-express a vector expressed in Ground into the same vector expressed in this body B, by applying only rotation. | |
Vec3 | expressVectorInAnotherBodyFrame (const State &s, const Vec3 &vectorInB, const MobilizedBody &inBodyA) const |
Re-express a vector expressed in this body B into the same vector expressed in body A, by applying only a rotation. | |
MassProperties | expressMassPropertiesInGroundFrame (const State &s) const |
Re-express this body B's mass properties in Ground by applying only a rotation, not a shift of reference point. | |
MassProperties | expressMassPropertiesInAnotherBodyFrame (const State &s, const MobilizedBody &inBodyA) const |
Re-express this body B's mass properties in another body A's frame by applying only a rotation, not a shift of reference point. | |
High-Level Operators | |
High level operators combine State Access and Basic Operators with run-time tests to calculate more complex MoblizedBody-specific quantities, with more complicated implementations that can exploit special cases at run time. | |
SpatialMat | calcBodySpatialInertiaMatrixInGround (const State &s) const |
Return the mass properties of body B, measured from and about the B frame origin, but expressed in Ground and then returned as a Spatial Inertia Matrix. | |
Inertia | calcBodyCentralInertia (const State &s, MobilizedBodyIndex objectBodyB) const |
Return the central inertia for body B, that is, the inertia taken about body B's mass center CB, and expressed in B. | |
Inertia | calcBodyInertiaAboutAnotherBodyStation (const State &s, const MobilizedBody &inBodyA, const Vec3 &aboutLocationOnBodyA) const |
Return the inertia of this body B, taken about an arbitrary point PA of body A, and expressed in body A. | |
SpatialVec | calcBodyMomentumAboutBodyOriginInGround (const State &s) |
Calculate body B's momentum (angular, linear) measured and expressed in ground, but taken about the body origin OB. | |
SpatialVec | calcBodyMomentumAboutBodyMassCenterInGround (const State &s) const |
Calculate body B's momentum (angular, linear) measured and expressed in ground, but taken about the body mass center CB. | |
Real | calcStationToStationDistance (const State &s, const Vec3 &locationOnBodyB, const MobilizedBody &bodyA, const Vec3 &locationOnBodyA) const |
Calculate the distance from a station PB on body B to a station PA on body A. | |
Real | calcStationToStationDistanceTimeDerivative (const State &s, const Vec3 &locationOnBodyB, const MobilizedBody &bodyA, const Vec3 &locationOnBodyA) const |
Calculate the time rate of change of distance from a fixed point PB on body B to a fixed point PA on body A. | |
Real | calcStationToStationDistance2ndTimeDerivative (const State &s, const Vec3 &locationOnBodyB, const MobilizedBody &bodyA, const Vec3 &locationOnBodyA) const |
Calculate the second time derivative of distance from a fixed point PB on body B to a fixed point PA on body A. | |
Vec3 | calcBodyMovingPointVelocityInBody (const State &s, const Vec3 &locationOnBodyB, const Vec3 &velocityOnBodyB, const MobilizedBody &inBodyA) const |
TODO: not implemented yet -- any volunteers? Return the velocity of a point P moving on body B, in body A's frame, expressed in body A. | |
Vec3 | calcBodyMovingPointAccelerationInBody (const State &s, const Vec3 &locationOnBodyB, const Vec3 &velocityOnBodyB, const Vec3 &accelerationOnBodyB, const MobilizedBody &inBodyA) const |
TODO: not implemented yet -- any volunteers? Return the velocity of a point P moving (and possibly accelerating) on body B, in body A's frame, expressed in body A. | |
Real | calcMovingPointToPointDistanceTimeDerivative (const State &s, const Vec3 &locationOnBodyB, const Vec3 &velocityOnBodyB, const MobilizedBody &bodyA, const Vec3 &locationOnBodyA, const Vec3 &velocityOnBodyA) const |
TODO: not implemented yet -- any volunteers? Calculate the time rate of change of distance from a moving point PB on body B to a moving point PA on body A. | |
Real | calcMovingPointToPointDistance2ndTimeDerivative (const State &s, const Vec3 &locationOnBodyB, const Vec3 &velocityOnBodyB, const Vec3 &accelerationOnBodyB, const MobilizedBody &bodyA, const Vec3 &locationOnBodyA, const Vec3 &velocityOnBodyA, const Vec3 &accelerationOnBodyA) const |
TODO: not implemented yet -- any volunteers? Calculate the second time derivative of distance from a moving point PB on body B to a moving point PA on body A. | |
Construction and Misc Methods | |
These methods are the base class services which are used while building a concrete MobilizedBody, or to query a MobilizedBody to find out how it was built. These are unlikely to be used by end users of MobilizedBodies. | |
MobilizedBody & | addBodyDecoration (const Transform &X_BD, const DecorativeGeometry &g) |
Add decorative geometry specified relative to the new (outboard) body's reference frame B, or to the outboard mobilizer frame M attached to body B, or to the inboard mobilizer frame F attached to the parent body P. | |
MobilizedBody & | addOutboardDecoration (const Transform &X_MD, const DecorativeGeometry &) |
Add decorative geometry specified relative to the outboard mobilizer frame M attached to body B. | |
MobilizedBody & | addInboardDecoration (const Transform &X_FD, const DecorativeGeometry &) |
Add decorative geometry specified relative to the inboard mobilizer frame F attached to the parent body P. | |
const Body & | getBody () const |
Return a reference to the Body contained within this MobilizedBody. | |
Body & | updBody () |
Return a writable reference to the Body contained within this MobilizedBody. | |
MobilizedBody & | setBody (const Body &) |
Replace the Body contained within this MobilizedBody with a new one. | |
MobilizedBody & | setDefaultMassProperties (const MassProperties &m) |
If the contained Body can have its mass properties set to the supplied value m its mass properties are changed, otherwise the method fails. | |
const MassProperties & | getDefaultMassProperties () const |
Return the mass properties of the Body stored within this MobilizedBody. | |
void | adoptMotion (Motion &ownerHandle) |
Provide a unique Motion object for this MobilizedBody. | |
void | clearMotion () |
If there is a Motion object associated with this MobilizedBody it is removed; otherwise, nothing happens. | |
bool | hasMotion () const |
Check whether this MobilizedBody has an associated Motion object. | |
const Motion & | getMotion () const |
If there is a Motion object assocated with this MobilizedBody, this returns a const reference to it. | |
MobilizedBody & | setDefaultInboardFrame (const Transform &X_PF) |
Change this mobilizer's frame F on the parent body P. | |
MobilizedBody & | setDefaultOutboardFrame (const Transform &X_BM) |
Change this mobilizer's frame M fixed on this (the outboard) body B. | |
const Transform & | getDefaultInboardFrame () const |
Return a reference to this mobilizer's default for the frame F fixed on the parent body P, as the fixed Transform from P's body frame to the frame F fixed to P. | |
const Transform & | getDefaultOutboardFrame () const |
Return a reference to this MobilizedBody's default for mobilizer frame M, as the fixed Transform from this body B's frame to the frame M fixed on B. | |
operator MobilizedBodyIndex () const | |
This is an implicit conversion from MobilizedBody to MobilizedBodyIndex when needed. | |
MobilizedBodyIndex | getMobilizedBodyIndex () const |
Return the MobilizedBodyIndex of this MobilizedBody within the owning SimbodyMatterSubsystem. | |
const MobilizedBody & | getParentMobilizedBody () const |
Return a reference to the MobilizedBody serving as the parent body of the current MobilizedBody. | |
const MobilizedBody & | getBaseMobilizedBody () const |
Return a reference to this MobilizedBody's oldest ancestor other than Ground, or return Ground if this MobilizedBody is Ground. | |
const SimbodyMatterSubsystem & | getMatterSubsystem () const |
Obtain a reference to the SimbodyMatterSubsystem which contains this MobilizedBody. | |
SimbodyMatterSubsystem & | updMatterSubsystem () |
Obtain a writable reference to the SimbodyMatterSubsystem which contains this MobilizedBody. | |
bool | isInSubsystem () const |
Determine whether the current MobilizedBody object is owned by a matter subsystem. | |
bool | isInSameSubsystem (const MobilizedBody &) const |
Determine whether a given MobilizedBody mBody is in the same matter subsystem as the current body. | |
bool | isSameMobilizedBody (const MobilizedBody &mBody) const |
Determine whether a given MobilizedBody mBody is the same MobilizedBody as this one. | |
bool | isGround () const |
Determine whether this body is Ground, meaning that it is actually body 0 of some matter subsytem, not just that its body type is Ground. | |
int | getLevelInMultibodyTree () const |
Return this body's level in the tree of bodies, starting with ground at 0, bodies directly connected to ground at 1, bodies directly connected to those at 2, etc. | |
MobilizedBody & | cloneForNewParent (MobilizedBody &parent) const |
Create a new MobilizedBody which is identical to this one, except that it has a different parent (and consequently might belong to a different MultibodySystem). | |
Real | getOneFromQPartition (const State &, int which, const Vector &qlike) const |
This utility selects one of the q's (generalized coordinates) associated with this mobilizer from a supplied "q-like" Vector, meaning a Vector which is the same length as the Vector of q's for the containing matter subsystem. | |
Real & | updOneFromQPartition (const State &, int which, Vector &qlike) const |
This utility returns a writable reference to one of the q's (generalized coordinates) associated with this mobilizer from a supplied "q-like" Vector, meaning a Vector which is the same length as the Vector of q's for the containing matter subsystem. | |
Real | getOneFromUPartition (const State &, int which, const Vector &ulike) const |
This utility selects one of the u's (generalized speeds) associated with this mobilizer from a supplied "u-like" Vector, meaning a Vector which is the same length as the Vector of u's for the containing matter subsystem. | |
Real & | updOneFromUPartition (const State &, int which, Vector &ulike) const |
This utility returns a writable reference to one of the u's (generalized speeds) associated with this mobilizer from a supplied "u-like" Vector, meaning a Vector which is the same length as the Vector of u's for the containing matter subsystem. | |
void | applyOneMobilityForce (const State &s, int which, Real f, Vector &mobilityForces) const |
This utility adds in the supplied generalized force force (a scalar) to the appropriate slot of the supplied mobilityForces Vector, which is a "u-like" Vector. | |
void | applyBodyForce (const State &s, const SpatialVec &spatialForceInG, Vector_< SpatialVec > &bodyForcesInG) const |
This utility adds in the supplied spatial force spatialForceInG (consisting of a torque vector, and a force vector to be applied at the current body's origin) to the appropriate slot of the supplied bodyForcesInG Vector. | |
void | applyBodyTorque (const State &s, const Vec3 &torqueInG, Vector_< SpatialVec > &bodyForcesInG) const |
This utility adds in the supplied pure torque torqueInG to the appropriate slot of the supplied bodyForcesInG Vector. | |
void | applyForceToBodyPoint (const State &s, const Vec3 &pointInB, const Vec3 &forceInG, Vector_< SpatialVec > &bodyForcesInG) const |
This utility adds in the supplied force forceInG applied at a point pointInB to the appropriate slot of the supplied bodyForcesInG Vector. | |
Related Functions | |
(Note that these are not member functions.) | |
typedef MobilizedBody | Mobod |
This is the approved abbreviation for MobilizedBody. Feel free to use it if you get tired of typing or seeing the full name. |
This is the base class for all MobilizedBody classes, which include a body and a particular kind of mobilizer (joint) connecting that body to its parent.
Each built-in MobilizedBody type is a local subclass within MobilizedBody, so the built-ins have names like MobilizedBody::Pin. All concrete MobilizedBodies, including the built-ins, are derived from MobilizedBody.
There are three sets of methods used for obtaining MobilizedBody-specific data from the containing System's State. These are:
State Access methods simply extract already-calculated data from the State or State Cache, or set State values. They involve no additional computation, have names beginning with "get" and "upd" (update) and return references to the requested quantities rather than calculated values. We divide these into routines which deal with bodies and routines which deal with mobilizers and mobilities.
Basic Operators use State Access methods to compute basic quantities which cannot be precomputed, such as the velocity of an arbitrary point, using an inline combination of basic floating point operations which can be reliably determined at compile time. These have names beginning with "find" or a more specific verb, as a reminder that they do not require a great deal of computation.
High Level Operators combine responses and basic operators with run-time tests to calculate more complex quantities, with more complicated implementations that can exploit special cases at run time. These begin with "calc" (calculate) as a reminder that they may involve substantial run time computation.
There is also a set of methods used for construction, and miscellaneous utilities. These methods are primarly intended for use by concrete MobilizedBody classes and are not generally used by end users.
In the API below, we'll refer to the current ("this") MobilizedBody as "body B". It is the "object" or "main" body with which we are concerned. Often there will be another body mentioned in the argument list as a target for some conversion. That "another" body will be called "body A". The Ground body is abbreviated "G".
We use OF to mean "the origin of frame F", CB is "the mass center of body B". R_AF is the rotation matrix giving frame F's orientation in frame A, such that a vector v expressed in F is reexpressed in A by v_A = R_AF * v_F. X_AF is the spatial transform giving frame F's origin location and orientation in frame A, such that a point P whose location is measured from F's origin OF and expressed in F by position vector p_FP (or more explicitly p_OF_P) is remeasured from frame A's origin OA and reexpressed in A via p_AP = X_AF * p_FP, where p_AP==p_OA_P.
typedef Pin SimTK::MobilizedBody::Torsion |
typedef Translation2D SimTK::MobilizedBody::Cartesian2D |
typedef Translation2D SimTK::MobilizedBody::CartesianCoords2D |
typedef TorsionStretch SimTK::MobilizedBody::ConicalCoords2D |
typedef Ball SimTK::MobilizedBody::Spherical |
Constructors can take an argument of this type to indicate that the mobilizer is being defined in the reverse direction, meaning from child to parent.
That means that the mobilizer coordinates and speeds will be defined as though the tree had been built in the opposite direction. This is a topological setting and can't be changed dynamically.
SimTK::MobilizedBody::MobilizedBody | ( | ) |
The default constructor initializes the base class so that it contains a null implementation.
This should be called only from concrete MobilizedBody constructors.
SimTK::MobilizedBody::MobilizedBody | ( | MobilizedBodyImpl * | r | ) | [explicit] |
Internal use only.
MobilizedBody& SimTK::MobilizedBody::setDefaultMotionType | ( | Motion::Level | , |
Motion::Method | = Motion::Prescribed |
||
) |
The default behavior of this mobilizer will normally be determined by whether you provide a Motion object for it.
However, you can override that afterwards.
void SimTK::MobilizedBody::setMotionType | ( | State & | , |
Motion::Level | , | ||
Motion::Method | = Motion::Prescribed |
||
) | const |
This is an Instance stage setting.
bool SimTK::MobilizedBody::isAccelerationAlwaysZero | ( | const State & | ) | const |
bool SimTK::MobilizedBody::isVelocityAlwaysZero | ( | const State & | ) | const |
Extract from the state cache the already-calculated spatial configuration X_GB of body B's body frame, measured with respect to the Ground frame and expressed in the Ground frame.
That is, we return the location of the body frame's origin, and the orientation of its x, y, and z axes, as the Transform X_GB. This notation is intended to convey unambiguously the sense of this transform, which is as follows: if you have a station (body fixed point) S on body B, represented by position vector p_BS (a.k.a. p_OB_S) from the origin OB of B to the point S and expressed in the B frame, then p_GS=X_GB*p_BS where p_GS (== p_OG_S) is the position vector from the Ground origin OG to the point in space currently coincident with S and expressed in the Ground frame. The inverse transformation is obtained using the "~" operator where ~X_GB=X_BG, so that p_BS = ~X_GB*p_GS. This response is available at Position stage.
Extract from the state cache the already-calculated spatial orientation R_GB of body B's body frame x, y, and z axes expressed in the Ground frame, as the Rotation matrix R_GB.
The sense of this rotation matrix is such that if you have a vector v fixed on body B, represented by the vector v_B expressed in the B frame, then v_G=R_GB*v_B where v_G is the same vector but re-expressed in the Ground frame. The inverse transformation is obtained using the "~" operator where ~R_GB=R_BG, so that v_B = ~R_GB*v_G. This response is available at Position stage.
At stage Position or higher, return the cross-mobilizer transform X_FM, the body's inboard mobilizer frame M measured and expressed in the parent body's corresponding outboard frame F.
const SpatialVec& SimTK::MobilizedBody::getBodyVelocity | ( | const State & | ) | const |
Extract from the state cache the already-calculated spatial velocity V_GB of this body's reference frame B, measured with respect to the Ground frame and expressed in the Ground frame.
That is, we return the linear velocity v_GB of the body frame's origin in G, and the body's angular velocity w_GB as the spatial velocity vector V_GB = {w_GB, v_GB}. This response is available at Velocity stage.
const SpatialVec& SimTK::MobilizedBody::getMobilizerVelocity | ( | const State & | ) | const |
At stage Velocity or higher, return the cross-mobilizer velocity V_FM, the relative velocity of this body's "moving" mobilizer frame M in the parent body's corresponding "fixed" frame F, measured and expressed in F.
Note that this isn't the usual spatial velocity since it isn't expressed in G.
Reimplemented in SimTK::MobilizedBody::Translation.
const SpatialVec& SimTK::MobilizedBody::getBodyAcceleration | ( | const State & | s | ) | const |
Extract from the state cache the already-calculated spatial acceleration A_GB of this body's reference frame B, measured with respect to the Ground frame and expressed in the Ground frame.
That is, we return the linear acceleration a_GB of the body frame's origin in G, and the body's angular acceleration b_GB as the spatial acceleration vector A_GB = {b_GB, a_GB}. This response is available at Acceleration stage.
const SpatialVec& SimTK::MobilizedBody::getMobilizerAcceleration | ( | const State & | ) | const [inline] |
TODO: Not implemented yet -- any volunteers? At stage Acceleration, return the cross-mobilizer acceleration A_FM, the relative acceleration of body B's "moving" mobilizer frame M in the parent body's corresponding "fixed" frame F, measured and expressed in F.
Note that this isn't the usual spatial acceleration since it isn't expressed in G.
Reimplemented in SimTK::MobilizedBody::Translation.
const MassProperties& SimTK::MobilizedBody::getBodyMassProperties | ( | const State & | ) | const |
Return a reference to this body's mass properties in the State cache.
The State must have been realized to Stage::Instance or higher.
Real SimTK::MobilizedBody::getBodyMass | ( | const State & | s | ) | const [inline] |
Return the mass of this body. The State must have been realized to Stage::Instance.
Return this body's center of mass station (i.e., the vector fixed in the body, going from body origin to body mass center, expressed in the body frame.) The State must have been realized to Stage::Instance or higher.
const Inertia& SimTK::MobilizedBody::getBodyInertiaAboutBodyOrigin | ( | const State & | s | ) | const [inline] |
Return a reference to this body's inertia matrix in the State cache, taken about the body origin and expressed in the body frame.
The State must have been realized to Stage::Instance or higher.
Return a reference to this mobilizer's frame F fixed on the parent body P, as the fixed Transform from P's body frame to the frame F fixed to P.
If this frame is changeable, the result comes from the State cache, otherwise it is from the MobilizedBody object itself. The State must have been realized to Stage::Instance or higher.
Return a reference to this MobilizedBody's mobilizer frame M, as the fixed Transform from this body B's frame to the frame M fixed on B.
If this frame is changeable, the result comes from the State cache, otherwise it is from the MobilizedBody object itself. The State must have been realized to Stage::Instance or higher.
TODO: not implemented yet.
Set the location and orientation of the inboard (parent) mobilizer frame F, fixed to this mobilizer's parent body P.
TODO: not implemented yet.
Set the location and orientation of the outboard mobilizer frame M, fixed to this body B.
int SimTK::MobilizedBody::getNumQ | ( | const State & | ) | const |
Return the number of generalized coordinates q currently in use by this mobilizer.
State must have been realized to Stage::Model.
int SimTK::MobilizedBody::getNumU | ( | const State & | ) | const |
Return the number of generalized speeds u currently in use by this mobilizer.
State must have been realized to Stage::Model.
Return the global QIndex of the first q for this mobilizer; all the q's range from getFirstQIndex() to QIndex(getFirstQIndex()+getNumQ()-1).
Return the global UIndex of the first u for this mobilizer; all the u's range from getFirstUIndex() to UIndex(getFirstUIndex()+getNumU()-1).
Real SimTK::MobilizedBody::getOneQ | ( | const State & | , |
int | which | ||
) | const |
Real SimTK::MobilizedBody::getOneU | ( | const State & | , |
int | which | ||
) | const |
Real SimTK::MobilizedBody::getOneQDot | ( | const State & | , |
int | which | ||
) | const |
Real SimTK::MobilizedBody::getOneUDot | ( | const State & | , |
int | which | ||
) | const |
Real SimTK::MobilizedBody::getOneQDotDot | ( | const State & | , |
int | which | ||
) | const |
Return the tau forces resulting from known (prescribed) acceleration, corresponding to each of this mobilizer's mobilities, as a Vector of length getNumU().
If this mobilizer has known accelerations (UDots) due to an active Motion object, the set of generalized forces tau that must be added in order to produce those accelerations is calculated at Acceleration stage. There is one scalar tau per mobility and they can be returned individually or as a Vector. The return value is zero if the accelerations are free.
Real SimTK::MobilizedBody::getOneTau | ( | const State & | , |
MobilizerUIndex | which | ||
) | const |
Return one of the tau forces resulting from known (prescribed) acceleration, corresponding to one of this mobilizer's mobilities as selected here using the which
parameter, numbered from zero to getNumU()-1.
void SimTK::MobilizedBody::setOneQ | ( | State & | , |
int | which, | ||
Real | v | ||
) | const |
void SimTK::MobilizedBody::setOneU | ( | State & | , |
int | which, | ||
Real | v | ||
) | const |
Adjust this mobilizer's q's to best approximate the supplied Transform which requests a particular relative orientation and translation between the "fixed" and "moving" frames connected by this mobilizer.
This set of methods sets the generalized coordinates, or speeds (state variables) for just the mobilizer associated with this MobilizedBody (ignoring all other mobilizers and constraints), without requiring knowledge of the meanings of the individual state variables. The idea here is to provide a physically-meaningful quantity relating the mobilizer's inboard and outboard frames, and then ask the mobilizer to set its state variables to reproduce that quantity to the extent it can.
These routines can be called in Stage::Model, however the routines may consult the current values of the state variables in some cases, so you must make sure they have been set to reasonable, or at least innocuous values (zero will work). In no circumstance will any of these routines look at any state variables which belong to another mobilizer; they are limited to working locally with one mobilizer.
Routines which specify only translation (linear velocity) may use rotational coordinates to help satisfy the translation requirement. An alternate "Only" method is available to forbid modification of purely rotational coordinates in that case. When a mobilizer uses state variables which have combined rotational and translational character (e.g. a screw joint) consult the documentation for the mobilizer to find out how it responds to these routines.
There is no guarantee that the desired physical quantity will be achieved by these routines; you can check on return if you're worried. Individual mobilizers make specific promises about what they will do; consult the documentation. These routines do not throw exceptions even for absurd requests like specifying a rotation for a sliding mobilizer. Nothing happens if there are no mobilities here, i.e. Ground or a Weld mobilizer.
Adjust this mobilizer's q's to best approximate the supplied Rotation matrix which requests a particular relative orientation between the "fixed" and "moving" frames connected by this mobilizer.
Adjust this mobilizer's q's to best approximate the supplied position vector which requests a particular offset between the origins of the "fixed" and "moving" frames connected by this mobilizer, with any q's (rotational or translational) being modified if doing so helps satisfy the request.
void SimTK::MobilizedBody::setUToFitVelocity | ( | State & | , |
const SpatialVec & | V_FM | ||
) | const |
Adjust this mobilizer's u's (generalized speeds) to best approximate the supplied spatial velocity V_FM
which requests the relative angular and linear velocity between the "fixed" and "moving" frames connected by this mobilizer.
Routines which affect generalized speeds u depend on the generalized coordinates q already having been set; they never change these coordinates.
Adjust this mobilizer's u's (generalized speeds) to best approximate the supplied angular velocity w_FM
which requests a particular relative angular between the "fixed" and "moving" frames connected by this mobilizer.
Adjust any of this mobilizer's u's (generalized speeds) to best approximate the supplied linear velocity v_FM
which requests a particular velocity for the "moving" frame M origin in the "fixed" frame F on the parent where these are the frames connected by this mobilizer.
SpatialVec SimTK::MobilizedBody::getHCol | ( | const State & | s, |
MobilizerUIndex | ux | ||
) | const |
Expert use only: obtain a column of the hinge matrix H corresponding to one of this mobilizer's mobilities (actually a column of H_PB_G; what Jain calls H* and Schwieters calls H^T).
This is the matrix that maps generalized speeds u to the cross-body relative spatial velocity V_PB_G via V_PB_G=H*u. Note that although H relates child body B to parent body B, it is expressed in the ground frame G so the resulting cross- body velocity of B in P is also expressed in G. The supplied state must have been realized through Position stage because H varies with this mobilizer's generalized coordinates q.
SpatialVec SimTK::MobilizedBody::getH_FMCol | ( | const State & | s, |
MobilizerUIndex | ux | ||
) | const |
Expert use only: obtain a column of the mobilizer-local hinge matrix H_FM which maps generalized speeds u to cross-mobilizer spatial velocity V_FM via V_FM=H_FM*u.
Note that H and V here are expressed in the parent body's (inboard) frame F. The supplied state must have been realized through Position stage because H varies with this mobilizer's generalized coordinates q.
Transform SimTK::MobilizedBody::findBodyTransformInAnotherBody | ( | const State & | s, |
const MobilizedBody & | inBodyA | ||
) | const [inline] |
These methods use state variables and Response methods to compute basic quantities which cannot be precomputed, but which can be implemented with an inline combination of basic floating point operations which can be reliably determined at compile time.
The method names and descriptions use the following terms:
Rotation SimTK::MobilizedBody::findBodyRotationInAnotherBody | ( | const State & | s, |
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Return R_AB, the rotation matrix giving this body B's axes in body A's frame.
Cost is 45 flops. If you know that one of the bodies is Ground, use the 0-cost response getBodyRotation() instead of this operators. This operator is available in Position stage.
Vec3 SimTK::MobilizedBody::findBodyOriginLocationInAnotherBody | ( | const State & | s, |
const MobilizedBody & | toBodyA | ||
) | const [inline] |
Return the station on another body A (that is, a point measured and expressed in A) that is currently coincident in space with the origin OB of this body B.
Cost is 18 flops. This operator is available at Position stage. Note: "findBodyOriginLocationInGround" doesn't exist because it would be the same as the response getBodyOriginLocation().
SpatialVec SimTK::MobilizedBody::findBodyVelocityInAnotherBody | ( | const State & | s, |
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Return the angular and linear velocity of body B's frame in body A's frame, expressed in body A, and arranged as a SpatialVec.
Cost is 51 flops. If you know inBodyA is Ground, don't use this routine; use the response method getBodyVelocity() which is free. This operator is available in Velocity stage.
Vec3 SimTK::MobilizedBody::findBodyAngularVelocityInAnotherBody | ( | const State & | s, |
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Return the angular velocity w_AB of body B's frame in body A's frame, expressed in body A.
Cost is 18 flops. If you know inBodyA is Ground, don't use this routine; use the response method getBodyAngularVelocity() which is free. This operator is available in Velocity stage.
Vec3 SimTK::MobilizedBody::findBodyOriginVelocityInAnotherBody | ( | const State & | s, |
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Return the velocity of body B's origin point in body A's frame, expressed in body A.
Cost is 51 flops. If you know inBodyA is Ground, don't use this routine; use the response method getBodyOriginVelocity() which is free. This operator is available in Velocity stage.
SpatialVec SimTK::MobilizedBody::findBodyAccelerationInAnotherBody | ( | const State & | s, |
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Return the angular and linear acceleration of body B's frame in body A's frame, expressed in body A, and arranged as a SpatialVec.
Cost is 105 flops. If you know that inBodyA is Ground, don't use this operator; instead, use the response method getBodyAcceleration() which is free. This operator is available in Acceleration stage.
Vec3 SimTK::MobilizedBody::findBodyAngularAccelerationInAnotherBody | ( | const State & | s, |
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Return the angular acceleration of body B's frame in body A's frame, expressed in body A.
Cost is 33 flops. If you know inBodyA
is Ground, don't use this operator; instead use the response method getBodyAngularAccleration() which is free. This operator is available at AccelerationStage.
Vec3 SimTK::MobilizedBody::findBodyOriginAccelerationInAnotherBody | ( | const State & | s, |
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Return the acceleration of body B's origin point in body A's frame, expressed in body A.
Cost is 105 flops. If you know that inBodyA is Ground, don't use this operator; instead, use the response method getBodyOriginAcceleration() which is free. This operator is available in Acceleration stage.
Vec3 SimTK::MobilizedBody::findStationLocationInGround | ( | const State & | s, |
const Vec3 & | stationOnB | ||
) | const [inline] |
Return the Cartesian (ground) location that is currently coincident with a station (point) S fixed on body B.
That is, we return locationInG= X_GB*stationOnB which means the result is measured from the Ground origin and expressed in Ground. In more precise notation, we're calculating p_GS = X_GB * p_BS for position vectors p_GS and p_BS. Cost is 18 flops. This operator is available at Position stage.
Vec3 SimTK::MobilizedBody::findStationLocationInAnotherBody | ( | const State & | s, |
const Vec3 & | stationOnB, | ||
const MobilizedBody & | toBodyA | ||
) | const [inline] |
Given a station S on this body B, return the location on another body A which is at the same location in space.
That is, we return locationOnA= X_AB*locationOnB, which means the result is measured from the body A origin and expressed in body A. In more precise notation, we're calculating p_AS = X_AB * p_BS, which we actually calculate as p_AS = X_AG*(X_GB*p_BS). Cost is 36 flops. Note: if you know that one of the bodies is Ground, use one of the routines above which is specialized for Ground to avoid half the work. This operator is available at Position stage or higher.
Vec3 SimTK::MobilizedBody::findStationVelocityInGround | ( | const State & | s, |
const Vec3 & | stationOnB | ||
) | const [inline] |
Given a station fixed on body B, return its inertial (Cartesian) velocity, that is, its velocity relative to the Ground frame, expressed in the Ground frame.
Cost is 27 flops. If you know the station is the body origin (0,0,0) don't use this routine; use the response getBodyOriginVelocity() which is free. This operator is available at Velocity stage.
Vec3 SimTK::MobilizedBody::findStationVelocityInAnotherBody | ( | const State & | s, |
const Vec3 & | stationOnBodyB, | ||
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Return the velocity of a station S fixed on body B, in body A's frame, expressed in body A.
Cost is 93 flops. If you know inBodyA
is Ground, don't use this operator; instead use the operator findStationVelocityInGround() which is much cheaper. This operator is available in Velocity stage.
Vec3 SimTK::MobilizedBody::findStationAccelerationInGround | ( | const State & | s, |
const Vec3 & | stationOnB | ||
) | const [inline] |
Given a station fixed on body B, return its inertial (Cartesian) acceleration, that is, its acceleration relative to the ground frame, expressed in the ground frame.
Cost is 48 flops. If you know the station is the body origin (0,0,0) don't use this routine; use the response getBodyOriginAcceleration() which is free. This operator is available at Acceleration stage.
Vec3 SimTK::MobilizedBody::findStationAccelerationInAnotherBody | ( | const State & | s, |
const Vec3 & | stationOnBodyB, | ||
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Return the acceleration of a station S fixed on body B, in another body A's frame, expressed in body A.
Cost is 186 flops. If you know that inBodyA
is Ground, don't use this operator; instead, use the operator findStationAccelerationInGround() which is much cheaper. This operator is available in Acceleration stage.
void SimTK::MobilizedBody::findStationLocationAndVelocityInGround | ( | const State & | s, |
const Vec3 & | locationOnB, | ||
Vec3 & | locationOnGround, | ||
Vec3 & | velocityInGround | ||
) | const [inline] |
It is cheaper to calculate a station's ground location and velocity together than to do them separately.
Here we can return them both in 30 flops, vs. 45 to do them in two calls. This operator is available at Velocity stage.
void SimTK::MobilizedBody::findStationLocationVelocityAndAccelerationInGround | ( | const State & | s, |
const Vec3 & | locationOnB, | ||
Vec3 & | locationOnGround, | ||
Vec3 & | velocityInGround, | ||
Vec3 & | accelerationInGround | ||
) | const [inline] |
It is cheaper to calculate a station's ground location, velocity, and acceleration together than to do them separately.
Here we can return them all in 54 flops, vs. 93 to do them in three calls. This operator is available at Acceleration stage.
Return the Cartesian (ground) location of this body B's mass center.
Cost is 18 flops. This operator is available at Position stage.
Vec3 SimTK::MobilizedBody::findMassCenterLocationInAnotherBody | ( | const State & | s, |
const MobilizedBody & | toBodyA | ||
) | const [inline] |
Return the point of another body A that is currently coincident in space with the mass center CB of this body B.
Cost is 36 flops. This operator is available at Position stage.
Vec3 SimTK::MobilizedBody::findStationAtGroundPoint | ( | const State & | s, |
const Vec3 & | locationInG | ||
) | const [inline] |
Return the station (point) S of this body B that is coincident with the given Ground location.
That is we return locationOnB = X_BG*locationInG, which means the result is measured from the body origin OB and expressed in the body frame. In more precise notation, we're calculating p_BS = X_BG*p_GS. Cost is 18 flops. This operator is available at Position stage.
Vec3 SimTK::MobilizedBody::findStationAtAnotherBodyStation | ( | const State & | s, |
const MobilizedBody & | fromBodyA, | ||
const Vec3 & | stationOnA | ||
) | const [inline] |
Return the station (point) on this body B that is coincident with the given station on another body A.
That is we return stationOnB = X_BA * stationOnA, which means the result is measured from the body origin OB and expressed in the body frame. Cost is 36 flops. This operator is available at Position stage.
Vec3 SimTK::MobilizedBody::findStationAtAnotherBodyOrigin | ( | const State & | s, |
const MobilizedBody & | fromBodyA | ||
) | const [inline] |
Return the station S of this body that is currently coincident in space with the origin OA of another body A.
Cost is 18 flops. This operator is available at Position stage.
Vec3 SimTK::MobilizedBody::findStationAtAnotherBodyMassCenter | ( | const State & | s, |
const MobilizedBody & | fromBodyA | ||
) | const [inline] |
Return the station S of this body that is currently coincident in space with the mass center CA of another body B.
Cost is 36 flops. This operator is available at Position stage.
Transform SimTK::MobilizedBody::findFrameTransformInGround | ( | const State & | s, |
const Transform & | frameOnB | ||
) | const [inline] |
Return the current Ground-frame pose (position and orientation) of a frame F that is fixed to body B.
That is, we return X_GF=X_GB*X_BF. Cost is 63 flops. This operator is available at Position stage.
SpatialVec SimTK::MobilizedBody::findFrameVelocityInGround | ( | const State & | s, |
const Transform & | frameOnB | ||
) | const [inline] |
Return the current Ground-frame spatial velocity V_GF (that is, angular and linear velocity) of a frame F that is fixed to body B.
The angular velocity of F is the same as that of B, but the linear velocity is the velocity of F's origin OF rather than B's origin OB. This operator is available at Velocity stage. Cost is 27 flops.
SpatialVec SimTK::MobilizedBody::findFrameAccelerationInGround | ( | const State & | s, |
const Transform & | frameOnB | ||
) | const [inline] |
Return the current Ground-frame spatial acceleration A_GF (that is, angular and linear acceleration) of a frame F that is fixed to body B.
The angular acceleration of F is the same as that of B, but the linear acceleration is the acceleration of F's origin OF rather than B's origin OB. This operator is available at Acceleration stage. Cost is 48 flops.
Vec3 SimTK::MobilizedBody::expressVectorInGroundFrame | ( | const State & | s, |
const Vec3 & | vectorInB | ||
) | const [inline] |
Re-express a vector expressed in this body B's frame into the same vector in G, by applying only a rotation.
That is, we return vectorInG = R_GB * vectorInB. Cost is 15 flops. This operator is available at Position stage.
Vec3 SimTK::MobilizedBody::expressGroundVectorInBodyFrame | ( | const State & | s, |
const Vec3 & | vectorInG | ||
) | const [inline] |
Re-express a vector expressed in Ground into the same vector expressed in this body B, by applying only rotation.
That is, we return vectorInB = R_BG * vectorInG. Cost is 15 flops. This operator is available at Position stage.
Vec3 SimTK::MobilizedBody::expressVectorInAnotherBodyFrame | ( | const State & | s, |
const Vec3 & | vectorInB, | ||
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Re-express a vector expressed in this body B into the same vector expressed in body A, by applying only a rotation.
That is, we return vectorInA = R_AB * vectorInB. Cost is 30 flops. This operator is available at Position stage. Note: if you know one of the bodies is Ground, call one of the specialized methods above to save 15 flops.
MassProperties SimTK::MobilizedBody::expressMassPropertiesInGroundFrame | ( | const State & | s | ) | const [inline] |
MassProperties SimTK::MobilizedBody::expressMassPropertiesInAnotherBodyFrame | ( | const State & | s, |
const MobilizedBody & | inBodyA | ||
) | const [inline] |
Re-express this body B's mass properties in another body A's frame by applying only a rotation, not a shift of reference point.
The mass properties remain measured in the body B frame, taken about the body B origin OB, but are reexpressed in A.
SpatialMat SimTK::MobilizedBody::calcBodySpatialInertiaMatrixInGround | ( | const State & | s | ) | const [inline] |
Return the mass properties of body B, measured from and about the B frame origin, but expressed in Ground and then returned as a Spatial Inertia Matrix.
The mass properties are arranged in the SpatialMat like this:
M=[ I_OB crossMat(m*CB) ] [ ~crossMat(m*CB) diag(m) ]
where I_OB is the inertia taken about the B frame origin OB, and CB is the vector r_OB_CB from B's origin to its mass center.
The Spatial Inertia Matrix for Ground has infinite mass and inertia, with the cross terms set to zero. That is, it looks like a 6x6 diagonal matrix with Infinity on the diagonals.
Stage::Position
, unless objectBodyB == GroundIndex
Inertia SimTK::MobilizedBody::calcBodyCentralInertia | ( | const State & | s, |
MobilizedBodyIndex | objectBodyB | ||
) | const [inline] |
Return the central inertia for body B, that is, the inertia taken about body B's mass center CB, and expressed in B.
Stage::Instance
Inertia SimTK::MobilizedBody::calcBodyInertiaAboutAnotherBodyStation | ( | const State & | s, |
const MobilizedBody & | inBodyA, | ||
const Vec3 & | aboutLocationOnBodyA | ||
) | const [inline] |
Return the inertia of this body B, taken about an arbitrary point PA of body A, and expressed in body A.
TODO: this needs testing!
SpatialVec SimTK::MobilizedBody::calcBodyMomentumAboutBodyOriginInGround | ( | const State & | s | ) | [inline] |
Calculate body B's momentum (angular, linear) measured and expressed in ground, but taken about the body origin OB.
SpatialVec SimTK::MobilizedBody::calcBodyMomentumAboutBodyMassCenterInGround | ( | const State & | s | ) | const [inline] |
Calculate body B's momentum (angular, linear) measured and expressed in ground, but taken about the body mass center CB.
Real SimTK::MobilizedBody::calcStationToStationDistance | ( | const State & | s, |
const Vec3 & | locationOnBodyB, | ||
const MobilizedBody & | bodyA, | ||
const Vec3 & | locationOnBodyA | ||
) | const [inline] |
Calculate the distance from a station PB on body B to a station PA on body A.
We are given the location vectors (stations) p_OB_PB and p_OA_PA, expressed in their respective frames. We return |p_PB_PA|.
Real SimTK::MobilizedBody::calcStationToStationDistanceTimeDerivative | ( | const State & | s, |
const Vec3 & | locationOnBodyB, | ||
const MobilizedBody & | bodyA, | ||
const Vec3 & | locationOnBodyA | ||
) | const [inline] |
Calculate the time rate of change of distance from a fixed point PB on body B to a fixed point PA on body A.
We are given the location vectors r_OB_PB and r_OA_PA, expressed in their respective frames. We return d/dt |r_OB_OA|, under the assumption that the time derivatives of the two given vectors in their own frames is zero.
Real SimTK::MobilizedBody::calcStationToStationDistance2ndTimeDerivative | ( | const State & | s, |
const Vec3 & | locationOnBodyB, | ||
const MobilizedBody & | bodyA, | ||
const Vec3 & | locationOnBodyA | ||
) | const [inline] |
Calculate the second time derivative of distance from a fixed point PB on body B to a fixed point PA on body A.
We are given the location vectors (stations) r_OB_PB and r_OA_PA, expressed in their respective frames. We return d^2/dt^2 |p_PB_PA|, under the assumption that the time derivatives of the two given vectors in their own frames is zero.
Vec3 SimTK::MobilizedBody::calcBodyMovingPointVelocityInBody | ( | const State & | s, |
const Vec3 & | locationOnBodyB, | ||
const Vec3 & | velocityOnBodyB, | ||
const MobilizedBody & | inBodyA | ||
) | const [inline] |
TODO: not implemented yet -- any volunteers? Return the velocity of a point P moving on body B, in body A's frame, expressed in body A.
Vec3 SimTK::MobilizedBody::calcBodyMovingPointAccelerationInBody | ( | const State & | s, |
const Vec3 & | locationOnBodyB, | ||
const Vec3 & | velocityOnBodyB, | ||
const Vec3 & | accelerationOnBodyB, | ||
const MobilizedBody & | inBodyA | ||
) | const [inline] |
TODO: not implemented yet -- any volunteers? Return the velocity of a point P moving (and possibly accelerating) on body B, in body A's frame, expressed in body A.
Real SimTK::MobilizedBody::calcMovingPointToPointDistanceTimeDerivative | ( | const State & | s, |
const Vec3 & | locationOnBodyB, | ||
const Vec3 & | velocityOnBodyB, | ||
const MobilizedBody & | bodyA, | ||
const Vec3 & | locationOnBodyA, | ||
const Vec3 & | velocityOnBodyA | ||
) | const [inline] |
TODO: not implemented yet -- any volunteers? Calculate the time rate of change of distance from a moving point PB on body B to a moving point PA on body A.
We are given the location vectors r_OB_PB and r_OA_PA, and the velocities of PB in B and PA in A, all expressed in their respective frames. We return d/dt |r_OB_OA|, taking into account the (given) time derivatives of the locations in their local frames, as well as the relative velocities of the bodies.
Real SimTK::MobilizedBody::calcMovingPointToPointDistance2ndTimeDerivative | ( | const State & | s, |
const Vec3 & | locationOnBodyB, | ||
const Vec3 & | velocityOnBodyB, | ||
const Vec3 & | accelerationOnBodyB, | ||
const MobilizedBody & | bodyA, | ||
const Vec3 & | locationOnBodyA, | ||
const Vec3 & | velocityOnBodyA, | ||
const Vec3 & | accelerationOnBodyA | ||
) | const [inline] |
TODO: not implemented yet -- any volunteers? Calculate the second time derivative of distance from a moving point PB on body B to a moving point PA on body A.
We are given the location vectors r_OB_PB and r_OA_PA, and the velocities and accelerations of PB in B and PA in A, all expressed in their respective frames. We return d^2/dt^2 |r_OA_OB|, taking into account the time derivatives of the locations in their local frames, as well as the relative velocities and accelerations of the bodies.
MobilizedBody& SimTK::MobilizedBody::addBodyDecoration | ( | const Transform & | X_BD, |
const DecorativeGeometry & | g | ||
) | [inline] |
Add decorative geometry specified relative to the new (outboard) body's reference frame B, or to the outboard mobilizer frame M attached to body B, or to the inboard mobilizer frame F attached to the parent body P.
Note that the body itself may already have had some decorative geometry on it when it was first put into this MobilizedBody; in that case this just adds more.
Reimplemented in SimTK::MobilizedBody::Pin, SimTK::MobilizedBody::Slider, SimTK::MobilizedBody::Screw, SimTK::MobilizedBody::Universal, SimTK::MobilizedBody::Cylinder, SimTK::MobilizedBody::BendStretch, SimTK::MobilizedBody::Planar, SimTK::MobilizedBody::SphericalCoords, SimTK::MobilizedBody::Gimbal, SimTK::MobilizedBody::Ball, SimTK::MobilizedBody::Ellipsoid, SimTK::MobilizedBody::Translation, SimTK::MobilizedBody::Free, SimTK::MobilizedBody::LineOrientation, SimTK::MobilizedBody::FreeLine, SimTK::MobilizedBody::Weld, and SimTK::MobilizedBody::Ground.
MobilizedBody& SimTK::MobilizedBody::addOutboardDecoration | ( | const Transform & | X_MD, |
const DecorativeGeometry & | |||
) |
Add decorative geometry specified relative to the outboard mobilizer frame M attached to body B.
If body B already has decorative geometry on it, this just adds some more.
Reimplemented in SimTK::MobilizedBody::Pin, SimTK::MobilizedBody::Slider, SimTK::MobilizedBody::Screw, SimTK::MobilizedBody::Universal, SimTK::MobilizedBody::Cylinder, SimTK::MobilizedBody::BendStretch, SimTK::MobilizedBody::Planar, SimTK::MobilizedBody::SphericalCoords, SimTK::MobilizedBody::Gimbal, SimTK::MobilizedBody::Ball, SimTK::MobilizedBody::Ellipsoid, SimTK::MobilizedBody::Translation, SimTK::MobilizedBody::Free, SimTK::MobilizedBody::LineOrientation, SimTK::MobilizedBody::FreeLine, and SimTK::MobilizedBody::Weld.
MobilizedBody& SimTK::MobilizedBody::addInboardDecoration | ( | const Transform & | X_FD, |
const DecorativeGeometry & | |||
) |
Add decorative geometry specified relative to the inboard mobilizer frame F attached to the parent body P.
If body P already has decorative geometry on it, this just adds some more.
Reimplemented in SimTK::MobilizedBody::Pin, SimTK::MobilizedBody::Slider, SimTK::MobilizedBody::Screw, SimTK::MobilizedBody::Universal, SimTK::MobilizedBody::Cylinder, SimTK::MobilizedBody::BendStretch, SimTK::MobilizedBody::Planar, SimTK::MobilizedBody::SphericalCoords, SimTK::MobilizedBody::Gimbal, SimTK::MobilizedBody::Ball, SimTK::MobilizedBody::Ellipsoid, SimTK::MobilizedBody::Translation, SimTK::MobilizedBody::Free, SimTK::MobilizedBody::LineOrientation, SimTK::MobilizedBody::FreeLine, and SimTK::MobilizedBody::Weld.
const Body& SimTK::MobilizedBody::getBody | ( | ) | const |
Return a reference to the Body contained within this MobilizedBody.
Body& SimTK::MobilizedBody::updBody | ( | ) |
Return a writable reference to the Body contained within this MobilizedBody.
Calling this method invalidates the MobilizedBody's topology, so the containing matter subsystem's realizeTopology() method must be called again.
MobilizedBody& SimTK::MobilizedBody::setBody | ( | const Body & | ) |
Replace the Body contained within this MobilizedBody with a new one.
Calling this method invalidates the MobilizedBody's topology, so the containing matter subsystem's realizeTopology() method must be called again. A reference to this MobilizedBody is returned so that this can be chained like an assignment operator.
MobilizedBody& SimTK::MobilizedBody::setDefaultMassProperties | ( | const MassProperties & | m | ) | [inline] |
If the contained Body can have its mass properties set to the supplied value m
its mass properties are changed, otherwise the method fails.
Calling this method invalidates the MobilizedBody's topology, so the containing matter subsystem's realizeTopology() method must be called again. A reference to this MobilizedBody is returned so that this can be chained like an assignment operator.
const MassProperties& SimTK::MobilizedBody::getDefaultMassProperties | ( | ) | const [inline] |
Return the mass properties of the Body stored within this MobilizedBody.
void SimTK::MobilizedBody::adoptMotion | ( | Motion & | ownerHandle | ) |
Provide a unique Motion object for this MobilizedBody.
The MobilizedBody takes over ownership of the Motion object and is responsible for cleaning up its heap space when the time comes. This is a Topology-changing operation and consequently requires write access to the MobilizedBody which will propagate to invalidate the containing Subsystem and System's topology. There can only be one Motion object per mobilizer; this method will throw an exception if there is already one here.
void SimTK::MobilizedBody::clearMotion | ( | ) |
If there is a Motion object associated with this MobilizedBody it is removed; otherwise, nothing happens.
If a Motion is deleted, the containing System's topology is invalidated.
bool SimTK::MobilizedBody::hasMotion | ( | ) | const |
Check whether this MobilizedBody has an associated Motion object.
This does not tell you whether the Motion object is currently enabled or in use; just whether it is available.
const Motion& SimTK::MobilizedBody::getMotion | ( | ) | const |
If there is a Motion object assocated with this MobilizedBody, this returns a const reference to it.
Otherwise it will throw an exception. You can check first using hasMotion(). Note that there is no provision to obtain a writable reference to the contained Motion object; if you want to change it clear the existing object instead and replace it with a new one.
MobilizedBody& SimTK::MobilizedBody::setDefaultInboardFrame | ( | const Transform & | X_PF | ) |
Change this mobilizer's frame F on the parent body P.
Calling this method invalidates the MobilizedBody's topology, so the containing matter subsystem's realizeTopology() method must be called again. A reference to this MobilizedBody is returned so that this can be chained like an assignment operator.
Reimplemented in SimTK::MobilizedBody::Pin, SimTK::MobilizedBody::Slider, SimTK::MobilizedBody::Screw, SimTK::MobilizedBody::Universal, SimTK::MobilizedBody::Cylinder, SimTK::MobilizedBody::BendStretch, SimTK::MobilizedBody::Planar, SimTK::MobilizedBody::SphericalCoords, SimTK::MobilizedBody::Gimbal, SimTK::MobilizedBody::Ball, SimTK::MobilizedBody::Ellipsoid, SimTK::MobilizedBody::Translation, SimTK::MobilizedBody::Free, SimTK::MobilizedBody::LineOrientation, SimTK::MobilizedBody::FreeLine, and SimTK::MobilizedBody::Weld.
MobilizedBody& SimTK::MobilizedBody::setDefaultOutboardFrame | ( | const Transform & | X_BM | ) |
Change this mobilizer's frame M fixed on this (the outboard) body B.
Calling this method invalidates the MobilizedBody's topology, so the containing matter subsystem's realizeTopology() method must be called again. A reference to this MobilizedBody is returned so that this can be chained like an assignment operator.
Reimplemented in SimTK::MobilizedBody::Pin, SimTK::MobilizedBody::Slider, SimTK::MobilizedBody::Screw, SimTK::MobilizedBody::Universal, SimTK::MobilizedBody::Cylinder, SimTK::MobilizedBody::BendStretch, SimTK::MobilizedBody::Planar, SimTK::MobilizedBody::SphericalCoords, SimTK::MobilizedBody::Gimbal, SimTK::MobilizedBody::Ball, SimTK::MobilizedBody::Ellipsoid, SimTK::MobilizedBody::Translation, SimTK::MobilizedBody::Free, SimTK::MobilizedBody::LineOrientation, SimTK::MobilizedBody::FreeLine, and SimTK::MobilizedBody::Weld.
const Transform& SimTK::MobilizedBody::getDefaultInboardFrame | ( | ) | const |
Return a reference to this mobilizer's default for the frame F fixed on the parent body P, as the fixed Transform from P's body frame to the frame F fixed to P.
This default Transform is stored with the MobilizedBody object, not the State.
const Transform& SimTK::MobilizedBody::getDefaultOutboardFrame | ( | ) | const |
Return a reference to this MobilizedBody's default for mobilizer frame M, as the fixed Transform from this body B's frame to the frame M fixed on B.
This default Transform is stored with the MobilizedBody object, not the State.
SimTK::MobilizedBody::operator MobilizedBodyIndex | ( | ) | const [inline] |
This is an implicit conversion from MobilizedBody to MobilizedBodyIndex when needed.
This will fail unless this MobilizedBody is owned by some SimbodyMatterSubsystem. We guarantee that the MobilizedBodyIndex of a mobilized body is numerically larger than the MobilizedBodyIndex of its parent.
MobilizedBodyIndex SimTK::MobilizedBody::getMobilizedBodyIndex | ( | ) | const |
Return the MobilizedBodyIndex of this MobilizedBody within the owning SimbodyMatterSubsystem.
This will fail unless this MobilizedBody is owned by some SimbodyMatterSubsystem. We guarantee that the MobilizedBodyIndex of a mobilized body is numerically larger than the MobilizedBodyIndex of its parent.
const MobilizedBody& SimTK::MobilizedBody::getParentMobilizedBody | ( | ) | const |
Return a reference to the MobilizedBody serving as the parent body of the current MobilizedBody.
This call will fail if the current MobilizedBody is Ground, since Ground has no parent.
const MobilizedBody& SimTK::MobilizedBody::getBaseMobilizedBody | ( | ) | const |
Return a reference to this MobilizedBody's oldest ancestor other than Ground, or return Ground if this MobilizedBody is Ground.
That is, we return the "base" MobilizedBody for this MobilizedBody, meaning the one which connects this branch of the multibody tree directly to Ground.
const SimbodyMatterSubsystem& SimTK::MobilizedBody::getMatterSubsystem | ( | ) | const |
Obtain a reference to the SimbodyMatterSubsystem which contains this MobilizedBody.
This will fail unless this MobilizedBody is owned by some SimbodyMatterSubsystem.
SimbodyMatterSubsystem& SimTK::MobilizedBody::updMatterSubsystem | ( | ) |
Obtain a writable reference to the SimbodyMatterSubsystem which contains this MobilizedBody.
This will fail unless this MobilizedBody is owned by some SimbodyMatterSubsystem.
bool SimTK::MobilizedBody::isInSubsystem | ( | ) | const |
Determine whether the current MobilizedBody object is owned by a matter subsystem.
bool SimTK::MobilizedBody::isInSameSubsystem | ( | const MobilizedBody & | ) | const |
Determine whether a given MobilizedBody mBody
is in the same matter subsystem as the current body.
If the bodies are not in a subsystem, this routine will return false
.
bool SimTK::MobilizedBody::isSameMobilizedBody | ( | const MobilizedBody & | mBody | ) | const |
Determine whether a given MobilizedBody mBody
is the same MobilizedBody as this one.
For this to be true the handles must not be empty, and the implementation objects must be the same object not separate objects with identical contents.
bool SimTK::MobilizedBody::isGround | ( | ) | const |
int SimTK::MobilizedBody::getLevelInMultibodyTree | ( | ) | const |
Return this body's level in the tree of bodies, starting with ground at 0, bodies directly connected to ground at 1, bodies directly connected to those at 2, etc.
This is callable after realizeTopology(). This is the graph distance of the body from Ground.
MobilizedBody& SimTK::MobilizedBody::cloneForNewParent | ( | MobilizedBody & | parent | ) | const |
Create a new MobilizedBody which is identical to this one, except that it has a different parent (and consequently might belong to a different MultibodySystem).
Real SimTK::MobilizedBody::getOneFromQPartition | ( | const State & | , |
int | which, | ||
const Vector & | qlike | ||
) | const |
This utility selects one of the q's (generalized coordinates) associated with this mobilizer from a supplied "q-like" Vector, meaning a Vector which is the same length as the Vector of q's for the containing matter subsystem.
Real& SimTK::MobilizedBody::updOneFromQPartition | ( | const State & | , |
int | which, | ||
Vector & | qlike | ||
) | const |
This utility returns a writable reference to one of the q's (generalized coordinates) associated with this mobilizer from a supplied "q-like" Vector, meaning a Vector which is the same length as the Vector of q's for the containing matter subsystem.
Real SimTK::MobilizedBody::getOneFromUPartition | ( | const State & | , |
int | which, | ||
const Vector & | ulike | ||
) | const |
This utility selects one of the u's (generalized speeds) associated with this mobilizer from a supplied "u-like" Vector, meaning a Vector which is the same length as the Vector of u's for the containing matter subsystem.
Real& SimTK::MobilizedBody::updOneFromUPartition | ( | const State & | , |
int | which, | ||
Vector & | ulike | ||
) | const |
This utility returns a writable reference to one of the u's (generalized speeds) associated with this mobilizer from a supplied "u-like" Vector, meaning a Vector which is the same length as the Vector of u's for the containing matter subsystem.
void SimTK::MobilizedBody::applyOneMobilityForce | ( | const State & | s, |
int | which, | ||
Real | f, | ||
Vector & | mobilityForces | ||
) | const [inline] |
This utility adds in the supplied generalized force force
(a scalar) to the appropriate slot of the supplied mobilityForces
Vector, which is a "u-like" Vector.
Note that we are adding this not setting it so it important that mobilityForces
be initialized to zero before making a set of calls to applyOneMobilityForce().
void SimTK::MobilizedBody::applyBodyForce | ( | const State & | s, |
const SpatialVec & | spatialForceInG, | ||
Vector_< SpatialVec > & | bodyForcesInG | ||
) | const |
This utility adds in the supplied spatial force spatialForceInG
(consisting of a torque vector, and a force vector to be applied at the current body's origin) to the appropriate slot of the supplied bodyForcesInG
Vector.
Note that we are adding this not setting it so it important that mobilityForces
be initialized to zero before making a set of calls to applyBodyForce().
void SimTK::MobilizedBody::applyBodyTorque | ( | const State & | s, |
const Vec3 & | torqueInG, | ||
Vector_< SpatialVec > & | bodyForcesInG | ||
) | const |
This utility adds in the supplied pure torque torqueInG
to the appropriate slot of the supplied bodyForcesInG
Vector.
Note that we are adding this not setting it so it important that bodyForcesInG
be initialized to zero before making a set of calls to applyBodyTorque().
void SimTK::MobilizedBody::applyForceToBodyPoint | ( | const State & | s, |
const Vec3 & | pointInB, | ||
const Vec3 & | forceInG, | ||
Vector_< SpatialVec > & | bodyForcesInG | ||
) | const |
This utility adds in the supplied force forceInG
applied at a point pointInB
to the appropriate slot of the supplied bodyForcesInG
Vector.
Notes:
bodyForcesInG
be initialized to zero before making a set of calls to applyForceToBodyPoint().pointInB
represents a fixed station of B and is provided by giving the vector from body B's origin to the point, expressed in the B frame, while the applied force (and resulting body forces and torques) are expressed in the ground frame. typedef MobilizedBody Mobod [related] |
This is the approved abbreviation for MobilizedBody. Feel free to use it if you get tired of typing or seeing the full name.