Simbody  3.6
SimTK::MobilizedBody::Custom Class Reference

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...

+ Inheritance diagram for SimTK::MobilizedBody::Custom:

Classes

class  Implementation
 This is the implementation class for Custom mobilizers. More...
 

Public Member Functions

 Custom ()
 Default constructor provides an empty handle that can be assigned to reference any MobilizedBody::Custom. More...
 
 Custom (MobilizedBody &parent, Implementation *implementation, const Transform &X_PF, const Body &bodyInfo, const Transform &X_BM, Direction direction=Forward)
 Create a Custom mobilizer between an existing parent (inboard) body P and a new child (outboard) body B created by copying the given bodyInfo into a privately-owned Body within the constructed MobilizedBody object. More...
 
 Custom (MobilizedBody &parent, Implementation *implementation, const Body &bodyInfo, Direction direction=Forward)
 Abbreviated constructor you can use if the mobilizer frames are coincident with the parent and child body frames. More...
 
- Public Member Functions inherited from SimTK::MobilizedBody
 MobilizedBody ()
 The default constructor provides an empty MobilizedBody handle that can be assigned to reference any type of MobilizedBody. More...
 
 MobilizedBody (MobilizedBodyImpl *r)
 Internal use only. More...
 
void lock (State &state, Motion::Level level=Motion::Position) const
 Lock this mobilizer's position or velocity at its current value, or lock the acceleration to zero, depending on the level parameter. More...
 
void lockAt (State &state, Real value, Motion::Level level=Motion::Position) const
 Lock this mobilizer's q, u, or udot to the given scalar value, depending on level. More...
 
void lockAt (State &state, const Vector &value, Motion::Level level=Motion::Position) const
 Lock this mobilizer's q, u, or udot to the given Vector value, depending on level. More...
 
template<int N>
void lockAt (State &state, const Vec< N > &value, Motion::Level level=Motion::Position) const
 Lock this mobilizer's q, u, or udot to the given Vec<N> value, depending on the level. More...
 
void unlock (State &state) const
 Unlock this mobilizer, returning it to its normal behavior which may be free motion or may be controlled by a Motion object. More...
 
bool isLocked (const State &state) const
 Check whether this mobilizer is currently locked in the given state. More...
 
Motion::Level getLockLevel (const State &state) const
 Returns the lock level if the mobilizer is locked in the given state, otherwise Motion::NoLevel. More...
 
Vector getLockValueAsVector (const State &state) const
 Return the q, u, or udot value at which this mobilizer is locked, depending on the lock level, as a Vector of the appropriate length. More...
 
MobilizedBodylockByDefault (Motion::Level level=Motion::Position)
 Change whether this mobilizer is initially locked. More...
 
bool isLockedByDefault () const
 Check whether this mobilizer is to be locked in the default state. More...
 
Motion::Level getLockByDefaultLevel () const
 Returns the level at which the mobilizer is locked by default, if it is locked by default, otherwise Motion::NoLevel. More...
 
const TransformgetBodyTransform (const State &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. More...
 
const RotationgetBodyRotation (const State &state) 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. More...
 
const Vec3getBodyOriginLocation (const State &state) const
 Extract from the state cache the already-calculated spatial location of body B's body frame origin Bo, measured from the Ground origin Go and expressed in the Ground frame, as the position vector p_GB (== p_GoBo). More...
 
const TransformgetMobilizerTransform (const State &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. More...
 
const SpatialVecgetBodyVelocity (const State &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. More...
 
const Vec3getBodyAngularVelocity (const State &state) 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. More...
 
const Vec3getBodyOriginVelocity (const State &state) const
 Extract from the state cache the already-calculated inertial linear velocity vector v_GB (more explicitly, v_GBo) of this body B's origin point Bo, measured with respect to the Ground frame and expressed in the Ground frame. More...
 
const SpatialVecgetMobilizerVelocity (const State &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. More...
 
const SpatialVecgetBodyAcceleration (const State &state) 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. More...
 
const Vec3getBodyAngularAcceleration (const State &state) 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. More...
 
const Vec3getBodyOriginAcceleration (const State &state) const
 Extract from the state cache the already-calculated inertial linear acceleration vector a_GB (more explicitly, a_GBo) of this body B's origin point Bo, measured with respect to the Ground frame and expressed in the Ground frame. More...
 
const SpatialVecgetMobilizerAcceleration (const State &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. More...
 
const MassPropertiesgetBodyMassProperties (const State &state) const
 Return a reference to this body's mass properties in the State cache. More...
 
const SpatialInertiagetBodySpatialInertiaInGround (const State &state) const
 Return a reference to the already-calculated SpatialInertia of this body, taken about the body's origin (not its mass center), and expressed in the Ground frame. More...
 
Real getBodyMass (const State &state) const
 Return the mass of this body. More...
 
const Vec3getBodyMassCenterStation (const State &state) 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. More...
 
const UnitInertiagetBodyUnitInertiaAboutBodyOrigin (const State &state) const
 Return a reference to this body's unit inertia matrix in the State cache, taken about the body origin and expressed in the body frame. More...
 
const TransformgetInboardFrame (const State &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. More...
 
const TransformgetOutboardFrame (const State &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. More...
 
void setInboardFrame (State &state, const Transform &X_PF) const
 TODO: not implemented yet. More...
 
void setOutboardFrame (State &state, const Transform &X_BM) const
 TODO: not implemented yet. More...
 
int getNumQ (const State &state) const
 Return the number of generalized coordinates q currently in use by this mobilizer. More...
 
int getNumU (const State &state) const
 Return the number of generalized speeds u currently in use by this mobilizer. More...
 
QIndex getFirstQIndex (const State &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). More...
 
UIndex getFirstUIndex (const State &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). More...
 
Motion::Method getQMotionMethod (const State &state) const
 Determine how generalized coordinate q values are being determined. More...
 
Motion::Method getUMotionMethod (const State &state) const
 Determine how generalized speed u values are being determined. More...
 
Motion::Method getUDotMotionMethod (const State &state) const
 Determine how generalized acceleration udot values are being determined. More...
 
Real getOneQ (const State &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. More...
 
Real getOneU (const State &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. More...
 
Vector getQAsVector (const State &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. More...
 
Vector getUAsVector (const State &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. More...
 
Real getOneQDot (const State &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. More...
 
Vector getQDotAsVector (const State &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 partition in the matter subsystem's full qdot vector in the State cache. More...
 
Real getOneUDot (const State &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. More...
 
Real getOneQDotDot (const State &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. More...
 
Vector getUDotAsVector (const State &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. More...
 
Vector getQDotDotAsVector (const State &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. More...
 
Vector getTauAsVector (const State &state) const
 Return the generalized forces tau resulting from prescribed (known) acceleration, corresponding to each of this mobilizer's mobilities, as a Vector of length nu=getNumU(). More...
 
Real getOneTau (const State &state, MobilizerUIndex which) const
 Return one of the tau forces resulting from prescribed (known) acceleration, corresponding to one of this mobilizer's mobilities as selected here using the which parameter, numbered from zero to getNumU()-1. More...
 
void setOneQ (State &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. More...
 
void setOneU (State &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. More...
 
void setQFromVector (State &state, 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. More...
 
void setUFromVector (State &state, 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. More...
 
void setQToFitTransform (State &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 F "fixed" frame and M "moving" frame connected by this mobilizer. More...
 
void setQToFitRotation (State &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" frame F and "moving" frame M connected by this mobilizer. More...
 
void setQToFitTranslation (State &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 F "fixed" frame and M "moving" frame connected by this mobilizer, with any q's (rotational or translational) being modified if doing so helps satisfy the request. More...
 
void setUToFitVelocity (State &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. More...
 
void setUToFitAngularVelocity (State &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. More...
 
void setUToFitLinearVelocity (State &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. More...
 
SpatialVec getHCol (const State &state, 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). More...
 
SpatialVec getH_FMCol (const State &state, 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. More...
 
Transform findBodyTransformInAnotherBody (const State &state, const MobilizedBody &inBodyA) const
 Return X_AB, the spatial transform giving this body B's frame in body A's frame. More...
 
Rotation findBodyRotationInAnotherBody (const State &state, const MobilizedBody &inBodyA) const
 Return R_AB, the rotation matrix giving this body B's axes in body A's frame. More...
 
Vec3 findBodyOriginLocationInAnotherBody (const State &state, 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 Bo of this body B. More...
 
SpatialVec findBodyVelocityInAnotherBody (const State &state, 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. More...
 
Vec3 findBodyAngularVelocityInAnotherBody (const State &state, const MobilizedBody &inBodyA) const
 Return the angular velocity w_AB of body B's frame in body A's frame, expressed in body A. More...
 
Vec3 findBodyOriginVelocityInAnotherBody (const State &state, const MobilizedBody &inBodyA) const
 Return the velocity of body B's origin point in body A's frame, expressed in body A. More...
 
SpatialVec findBodyAccelerationInAnotherBody (const State &state, 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. More...
 
Vec3 findBodyAngularAccelerationInAnotherBody (const State &state, const MobilizedBody &inBodyA) const
 Return the angular acceleration of body B's frame in body A's frame, expressed in body A. More...
 
Vec3 findBodyOriginAccelerationInAnotherBody (const State &state, const MobilizedBody &inBodyA) const
 Return the acceleration of body B's origin point in body A's frame, expressed in body A. More...
 
SpatialVec findMobilizerReactionOnBodyAtMInGround (const State &state) const
 Return the spatial reaction force (moment and force) applied by the mobilizer to body B at the location of the mobilizer frame M (fixed to body B, but not necessarily at the body frame origin), expressed in Ground. More...
 
SpatialVec findMobilizerReactionOnBodyAtOriginInGround (const State &state) const
 Return the spatial reaction force (moment and force) applied by the mobilizer to body B but shifted to the B frame origin, and expressed in Ground. More...
 
SpatialVec findMobilizerReactionOnParentAtFInGround (const State &state) const
 Return the spatial reaction force (moment and force) applied by the mobilizer to the parent (inboard) body P at the location of the inboard "fixed" mobilizer frame F (fixed to body P, but not necessarily at the P frame origin), expressed in Ground. More...
 
SpatialVec findMobilizerReactionOnParentAtOriginInGround (const State &state) const
 Return the spatial reaction force (moment and force) applied by the mobilizer to the parent (inboard) body P at the location of the P frame origin, and expressed in Ground. More...
 
Vec3 findStationLocationInGround (const State &state, const Vec3 &stationOnB) const
 Return the Cartesian (ground) location that is currently coincident with a station (point) S fixed on body B. More...
 
Vec3 findStationLocationInAnotherBody (const State &state, 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. More...
 
Vec3 findStationVelocityInGround (const State &state, 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. More...
 
Vec3 findStationVelocityInAnotherBody (const State &state, 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. More...
 
Vec3 findStationAccelerationInGround (const State &state, 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. More...
 
Vec3 findStationAccelerationInAnotherBody (const State &state, 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. More...
 
void findStationLocationAndVelocityInGround (const State &state, 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. More...
 
void findStationLocationVelocityAndAccelerationInGround (const State &state, 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. More...
 
Vec3 findMassCenterLocationInGround (const State &state) const
 Return the Cartesian (ground) location of this body B's mass center. More...
 
Vec3 findMassCenterLocationInAnotherBody (const State &state, 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. More...
 
Vec3 findStationAtGroundPoint (const State &state, const Vec3 &locationInG) const
 Return the station (point) S of this body B that is coincident with the given Ground location. More...
 
Vec3 findStationAtAnotherBodyStation (const State &state, 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. More...
 
Vec3 findStationAtAnotherBodyOrigin (const State &state, const MobilizedBody &fromBodyA) const
 Return the station S of this body that is currently coincident in space with the origin Ao of another body A. More...
 
Vec3 findStationAtAnotherBodyMassCenter (const State &state, const MobilizedBody &fromBodyA) const
 Return the station S of this body that is currently coincident in space with the mass center Ac of another body A. More...
 
Transform findFrameTransformInGround (const State &state, const Transform &frameOnB) const
 Return the current Ground-frame pose (position and orientation) of a frame F that is fixed to body B. More...
 
SpatialVec findFrameVelocityInGround (const State &state, 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. More...
 
SpatialVec findFrameAccelerationInGround (const State &state, 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. More...
 
Vec3 expressVectorInGroundFrame (const State &state, 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. More...
 
Vec3 expressGroundVectorInBodyFrame (const State &state, const Vec3 &vectorInG) const
 Re-express a vector expressed in Ground into the same vector expressed in this body B, by applying only rotation. More...
 
Vec3 expressVectorInAnotherBodyFrame (const State &state, 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. More...
 
MassProperties expressMassPropertiesInGroundFrame (const State &state) const
 Re-express this body B's mass properties in Ground by applying only a rotation, not a shift of reference point. More...
 
MassProperties expressMassPropertiesInAnotherBodyFrame (const State &state, 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. More...
 
SpatialMat calcBodySpatialInertiaMatrixInGround (const State &state) const
 Return the mass properties of body B, measured from and about the B origin Bo, but expressed in Ground and then returned as a Spatial Inertia Matrix. More...
 
Inertia calcBodyCentralInertia (const State &state, MobilizedBodyIndex objectBodyB) const
 Return the central inertia for body B, that is, the inertia taken about body B's mass center Bc, and expressed in B. More...
 
Inertia calcBodyInertiaAboutAnotherBodyStation (const State &state, 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. More...
 
SpatialVec calcBodyMomentumAboutBodyOriginInGround (const State &state)
 Calculate body B's momentum (angular, linear) measured and expressed in Ground, but taken about the body origin Bo. More...
 
SpatialVec calcBodyMomentumAboutBodyMassCenterInGround (const State &state) const
 Calculate body B's momentum (angular, linear) measured and expressed in Ground, but taken about the body mass center Bc. More...
 
Real calcStationToStationDistance (const State &state, 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. More...
 
Real calcStationToStationDistanceTimeDerivative (const State &state, 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. More...
 
Real calcStationToStationDistance2ndTimeDerivative (const State &state, 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. More...
 
Vec3 calcBodyMovingPointVelocityInBody (const State &state, 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. More...
 
Vec3 calcBodyMovingPointAccelerationInBody (const State &state, 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. More...
 
Real calcMovingPointToPointDistanceTimeDerivative (const State &state, 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. More...
 
Real calcMovingPointToPointDistance2ndTimeDerivative (const State &state, 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. More...
 
const BodygetBody () const
 Return a const reference to the Body contained within this MobilizedBody. More...
 
BodyupdBody ()
 Return a writable reference to the Body contained within this MobilizedBody. More...
 
MobilizedBodysetBody (const Body &)
 Replace the Body contained within this MobilizedBody with a new one. More...
 
int addBodyDecoration (const Transform &X_BD, const DecorativeGeometry &geometry)
 Convenience method to add DecorativeGeometry specified relative to the new (outboard) body's reference frame B. More...
 
int addBodyDecoration (const DecorativeGeometry &geometry)
 Convenience method for use when the geometry is supplied in the body frame. More...
 
int addOutboardDecoration (const Transform &X_MD, const DecorativeGeometry &geometry)
 Add decorative geometry specified relative to the outboard mobilizer frame M attached to body B, and associated with the mobilizer rather than the body. More...
 
int getNumOutboardDecorations () const
 Return the count of decorations added with addOutboardDecoration(). More...
 
const DecorativeGeometrygetOutboardDecoration (int i) const
 Return a const reference to the i'th outboard decoration. More...
 
DecorativeGeometryupdOutboardDecoration (int i)
 Return a writable reference to the i'th outboard decoration. More...
 
int addInboardDecoration (const Transform &X_FD, const DecorativeGeometry &geometry)
 Add decorative geometry specified relative to the inboard mobilizer frame F attached to the parent body P, and associated with the mobilizer rather than the body. More...
 
int getNumInboardDecorations () const
 Return the count of decorations added with addInboardDecoration(). More...
 
const DecorativeGeometrygetInboardDecoration (int i) const
 Return a const reference to the i'th inboard decoration. More...
 
DecorativeGeometryupdInboardDecoration (int i)
 Return a writable reference to the i'th inboard decoration. More...
 
MobilizedBodysetDefaultMassProperties (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. More...
 
const MassPropertiesgetDefaultMassProperties () const
 Return the mass properties of the Body stored within this MobilizedBody. More...
 
void adoptMotion (Motion &ownerHandle)
 Provide a unique Motion object for this MobilizedBody. More...
 
void clearMotion ()
 If there is a Motion object associated with this MobilizedBody it is removed; otherwise, nothing happens. More...
 
bool hasMotion () const
 Check whether this MobilizedBody has an associated Motion object. More...
 
const MotiongetMotion () const
 If there is a Motion object associated with this MobilizedBody, this returns a const reference to it. More...
 
MobilizedBodysetDefaultInboardFrame (const Transform &X_PF)
 Change this mobilizer's frame F on the parent body P. More...
 
MobilizedBodysetDefaultOutboardFrame (const Transform &X_BM)
 Change this mobilizer's frame M fixed on this (the outboard) body B. More...
 
const TransformgetDefaultInboardFrame () const
 Return a reference to this mobilizer's default for the frame F fixed on the parent (inboard) body P, as the fixed Transform from P's body frame to the frame F fixed to P. More...
 
const TransformgetDefaultOutboardFrame () 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. More...
 
 operator MobilizedBodyIndex () const
 This is an implicit conversion from MobilizedBody to MobilizedBodyIndex when needed. More...
 
MobilizedBodyIndex getMobilizedBodyIndex () const
 Return the MobilizedBodyIndex of this MobilizedBody within the owning SimbodyMatterSubsystem. More...
 
const MobilizedBodygetParentMobilizedBody () const
 Return a reference to the MobilizedBody serving as the parent body of the current MobilizedBody. More...
 
const MobilizedBodygetBaseMobilizedBody () const
 Return a reference to this MobilizedBody's oldest ancestor other than Ground, or return Ground if this MobilizedBody is Ground. More...
 
const SimbodyMatterSubsystemgetMatterSubsystem () const
 Obtain a reference to the SimbodyMatterSubsystem which contains this MobilizedBody. More...
 
SimbodyMatterSubsystemupdMatterSubsystem ()
 Obtain a writable reference to the SimbodyMatterSubsystem which contains this MobilizedBody. More...
 
bool isInSubsystem () const
 Determine whether the current MobilizedBody object is owned by a matter subsystem. More...
 
bool isInSameSubsystem (const MobilizedBody &mobod) const
 Determine whether a given MobilizedBody mobod is in the same matter subsystem as the current body. More...
 
bool isSameMobilizedBody (const MobilizedBody &mobod) const
 Determine whether a given MobilizedBody mobod is the same MobilizedBody as this one. More...
 
bool isGround () const
 Determine whether this MobilizedBody is Ground, meaning that it is actually body 0 of some matter subsytem, not just that its body type is Ground. More...
 
int getLevelInMultibodyTree () const
 Return this mobilized body's level in the tree of bodies, starting with Ground at 0, mobilized bodies directly connected to Ground at 1, mobilized bodies directly connected to those at 2, etc. More...
 
MobilizedBodycloneForNewParent (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). More...
 
Real getOneFromQPartition (const State &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. More...
 
RealupdOneFromQPartition (const State &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. More...
 
Real getOneFromUPartition (const State &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. More...
 
RealupdOneFromUPartition (const State &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. More...
 
void applyOneMobilityForce (const State &state, int which, Real f, Vector &mobilityForces) const
 This utility adds in the supplied generalized force f (a scalar) to the appropriate slot of the supplied mobilityForces Vector, which is a "u-like" Vector. More...
 
void convertQForceToUForce (const State &state, const Array_< Real, MobilizerQIndex > &fq, Array_< Real, MobilizerUIndex > &fu) const
 Given a generalized force in the q-space of this mobilizer, convert it to the equivalent generalized mobility force (u-space force). More...
 
void applyBodyForce (const State &state, 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. More...
 
void applyBodyTorque (const State &state, 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. More...
 
void applyForceToBodyPoint (const State &state, 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. More...
 
- Public Member Functions inherited from SimTK::PIMPLHandle< MobilizedBody, MobilizedBodyImpl, 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 MobilizedBody &other) const
 Determine whether the supplied handle is the same object as "this" PIMPLHandle. More...
 
void disown (MobilizedBody &newOwner)
 Give up ownership of the implementation to an empty handle. More...
 
PIMPLHandlereferenceAssign (const MobilizedBody &source)
 "Copy" assignment but with shallow (pointer) semantics. More...
 
PIMPLHandlecopyAssign (const MobilizedBody &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 MobilizedBodyImpl & getImpl () const
 Get a const reference to the implementation associated with this Handle. More...
 
MobilizedBodyImpl & 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...
 

Protected Member Functions

const ImplementationgetImplementation () const
 
ImplementationupdImplementation ()
 
- Protected Member Functions inherited from SimTK::PIMPLHandle< MobilizedBody, MobilizedBodyImpl, true >
 PIMPLHandle ()
 The default constructor makes this an empty handle. More...
 
 PIMPLHandle (MobilizedBodyImpl *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...
 
PIMPLHandleoperator= (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 (MobilizedBodyImpl *p)
 Set the implementation for this empty handle. More...
 
bool hasSameImplementation (const MobilizedBody &other) const
 Determine whether the supplied handle is a reference to the same implementation object as is referenced by "this" PIMPLHandle. More...
 

Additional Inherited Members

- Public Types inherited from SimTK::MobilizedBody
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 the outboard (child) body to the inboard (parent) body. More...
 
typedef Pin Torsion
 Synonym for Pin mobilizer. More...
 
typedef Pin Revolute
 Synonym for Pin mobilizer. More...
 
typedef Slider Prismatic
 Synonym for Slider mobilizer. More...
 
typedef Translation Cartesian
 Synonym for Translation mobilizer. More...
 
typedef Translation CartesianCoords
 Synonym for Translation mobilizer. More...
 
typedef BendStretch PolarCoords
 Synonym for BendStretch mobilizer. More...
 
typedef Ball Orientation
 Synonym for Ball mobilizer. More...
 
typedef Ball Spherical
 Synonym for Ball mobilizer. More...
 
- Public Types inherited from SimTK::PIMPLHandle< MobilizedBody, MobilizedBodyImpl, true >
typedef PIMPLHandle< MobilizedBody, MobilizedBodyImpl, PTR > HandleBase
 
typedef HandleBase ParentHandle
 

Detailed Description

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.

To use it, create a class that extends MobilizedBody::Custom::Implementation. You can then create an instance of it and pass it to the MobilizedBody::Custom constructor:

MobilizedBody::Custom myMobilizedBody(new MyMobilizedBodyImplementation(args));

("args" here and below stands for whatever arguments are needed for your particular mobilizer; it isn't meant literally.)

Alternatively, you can also create a new Handle class which is a subclass of MobilizedBody::Custom and which creates the Implementation itself in its constructors.

class MyMobilizedBody : public MobilizedBody::Custom {
public:
MyMobilizedBody(args)
: MobilizedBody::Custom(new MyMobilizedBodyImplementation(args)) {}
};

This allows an end user to simply write

MyMobilizedBody(args);

and not worry about implementation classes or creating objects on the heap. If you do this, your MobilizedBody::Custom subclass must not have any data members or virtual methods. If it does, it will not work correctly. Instead, store all data in the Implementation subclass.

See also
MobilizedBody::Custom::Implementation

Constructor & Destructor Documentation

◆ Custom() [1/3]

Default constructor provides an empty handle that can be assigned to reference any MobilizedBody::Custom.

◆ Custom() [2/3]

SimTK::MobilizedBody::Custom::Custom ( MobilizedBody parent,
Implementation implementation,
const Transform X_PF,
const Body bodyInfo,
const Transform X_BM,
Direction  direction = Forward 
)

Create a Custom mobilizer between an existing parent (inboard) body P and a new child (outboard) body B created by copying the given bodyInfo into a privately-owned Body within the constructed MobilizedBody object.

Specify the mobilizer frames F fixed to parent P and M fixed to child B.

See also
MobilizedBody for a diagram and explanation of terminology.
Parameters
parentthe MobilizedBody's parent (inboard) body
implementationthe object which implements the custom mobilized body. The MobilizedBody::Custom takes over ownership of the implementation object, and deletes it when the MobilizedBody itself is deleted.
X_PFthe MobilizedBody's F (inboard) frame
bodyInfodescribes this MobilizedBody's physical properties
X_BMthe MobilizedBody's M (outboard) frame
directionwhether you want the coordinates defined as though parent & child were swapped

◆ Custom() [3/3]

SimTK::MobilizedBody::Custom::Custom ( MobilizedBody parent,
Implementation implementation,
const Body bodyInfo,
Direction  direction = Forward 
)

Abbreviated constructor you can use if the mobilizer frames are coincident with the parent and child body frames.

Member Function Documentation

◆ getImplementation()

const Implementation& SimTK::MobilizedBody::Custom::getImplementation ( ) const
protected

◆ updImplementation()

Implementation& SimTK::MobilizedBody::Custom::updImplementation ( )
protected

The documentation for this class was generated from the following file: