1 #ifndef SimTK_SIMBODY_MATTER_SUBSYSTEM_H_ 2 #define SimTK_SIMBODY_MATTER_SUBSYSTEM_H_ 35 class SimbodyMatterSubsystemRep;
40 class MultibodySystem;
43 class UnilateralContact;
44 class StateLimitedFriction;
203 void setShowDefaultGeometry(
bool show);
206 bool getShowDefaultGeometry()
const;
225 int getNumBodies()
const;
230 int getNumConstraints()
const;
234 int getNumMobilities()
const;
238 int getTotalQAlloc()
const;
269 int getNumUnilateralContacts()
const;
274 int getNumStateLimitedFrictions()
const;
276 getStateLimitedFriction(StateLimitedFrictionIndex)
const;
278 updStateLimitedFriction(StateLimitedFrictionIndex);
302 void setUseEulerAngles(
State& state,
bool useEulerAngles)
const;
306 bool getUseEulerAngles(
const State& state)
const;
312 int getNumQuaternionsInUse(
const State& state)
const;
325 QuaternionPoolIndex getQuaternionPoolIndex(
const State& state,
334 void setConstraintIsDisabled(
State& state,
336 bool shouldDisableConstraint)
const;
349 void convertToEulerAngles(
const State& inputState,
State& outputState)
const;
357 void convertToQuaternions(
const State& inputState,
State& outputState)
const;
366 void normalizeQuaternions(
State& state)
const;
385 Real calcSystemMass(
const State& s)
const;
391 Vec3 calcSystemMassCenterLocationInGround(
const State& s)
const;
403 Inertia calcSystemCentralInertiaInGround(
const State& s)
const;
409 Vec3 calcSystemMassCenterVelocityInGround(
const State& s)
const;
415 Vec3 calcSystemMassCenterAccelerationInGround(
const State& s)
const;
438 Real calcKineticEnergy(
const State& state)
const;
554 void multiplyBySystemJacobian(
const State& state,
585 void calcBiasForSystemJacobian(
const State& state,
592 void calcBiasForSystemJacobian(
const State& state,
646 void multiplyBySystemJacobianTranspose(
const State& state,
683 void calcSystemJacobian(
const State& state,
690 void calcSystemJacobian(
const State& state,
739 void multiplyByStationJacobian(
const State& state,
749 const Vec3& stationPInB,
755 multiplyByStationJacobian(state, bodies, stations, u, JSu);
772 void multiplyByStationJacobianTranspose
780 void multiplyByStationJacobianTranspose
783 const Vec3& stationPInB,
790 multiplyByStationJacobianTranspose(state, bodies, stations, forces, f);
833 void calcStationJacobian(
const State& state,
841 const Vec3& stationPInB,
846 calcStationJacobian(state, bodies, stations, JS);
852 void calcStationJacobian(
const State& state,
860 const Vec3& stationPInB,
865 calcStationJacobian(state, bodies, stations, JS);
905 void calcBiasForStationJacobian(
const State& state,
913 void calcBiasForStationJacobian(
const State& state,
922 const Vec3& stationPInB)
const 927 calcBiasForStationJacobian(state, bodies, stations, JSDotu);
988 void multiplyByFrameJacobian
1000 const Vec3& originAoInB,
1006 multiplyByFrameJacobian(state, bodies, stations, u, JFu);
1053 void multiplyByFrameJacobianTranspose
1054 (
const State& state,
1064 const Vec3& originAoInB,
1071 multiplyByFrameJacobianTranspose(state, bodies, stations, forces, f);
1120 void calcFrameJacobian(
const State& state,
1129 const Vec3& originAoInB,
1134 calcFrameJacobian(state, bodies, stations, JF);
1140 void calcFrameJacobian(
const State& state,
1149 const Vec3& originAoInB,
1154 calcFrameJacobian(state, bodies, stations, JF);
1199 void calcBiasForFrameJacobian
1200 (
const State& state,
1208 void calcBiasForFrameJacobian(
const State& state,
1218 const Vec3& originAoInB)
const 1223 calcBiasForFrameJacobian(state, bodies, stations, JFDotu);
1343 void multiplyByMInv(
const State& state,
1428 void calcProjectedMInv(
const State& s,
1475 void solveForConstraintImpulses(
const State& state,
1507 calcBiasForMultiplyByG(state, bias);
1508 multiplyByG(state, ulike, bias, Gulike);
1515 void multiplyByG(
const State& state,
1545 void calcBiasForMultiplyByG(
const State& state,
1598 void calcBiasForAccelerationConstraints(
const State& state,
1635 void multiplyByGTranspose(
const State& state,
1650 void calcGTranspose(
const State&,
Matrix& Gt)
const;
1705 Vector& PqXqlike)
const {
1707 calcBiasForMultiplyByPq(state, biasp);
1708 multiplyByPq(state, qlike, biasp, PqXqlike);
1715 void multiplyByPq(
const State& state,
1736 void calcBiasForMultiplyByPq(
const State& state,
1766 void calcPq(
const State& state,
Matrix& Pq)
const;
1801 void multiplyByPqTranspose(
const State& state,
1832 void calcPqTranspose(
const State& state,
Matrix& Pqt)
const;
1855 void calcPt(
const State& state,
Matrix& Pt)
const;
1877 void multiplyByNInv(
const State& s,
bool transpose,
1889 void multiplyByNDot(
const State& s,
bool transpose,
1960 void calcAcceleration
1961 (
const State& state,
1962 const Vector& appliedMobilityForces,
1990 void calcAccelerationIgnoringConstraints
1991 (
const State& state,
1992 const Vector& appliedMobilityForces,
2053 void calcResidualForceIgnoringConstraints
2054 (
const State& state,
2055 const Vector& appliedMobilityForces,
2058 Vector& residualMobilityForces)
const;
2123 void calcResidualForce
2124 (
const State& state,
2125 const Vector& appliedMobilityForces,
2128 const Vector& knownLambda,
2129 Vector& residualMobilityForces)
const;
2142 void calcCompositeBodyInertias(
const State& state,
2184 void calcBodyAccelerationFromUDot(
const State& state,
2211 void calcConstraintForcesFromMultipliers
2212 (
const State& state,
2213 const Vector& multipliers,
2215 Vector& mobilityForces)
const;
2299 void calcMobilizerReactionForces
2300 (
const State& state,
2312 const Vector& getMotionMultipliers(
const State& state)
const;
2337 void findMotionForces
2338 (
const State& state,
2339 Vector& mobilityForces)
const;
2350 const Vector& getConstraintMultipliers(
const State& state)
const;
2359 void findConstraintForces
2360 (
const State& state,
2362 Vector& mobilityForces)
const;
2382 Real calcMotionPower(
const State& state)
const;
2413 Real calcConstraintPower(
const State& state)
const;
2420 void calcTreeEquivalentMobilityForces(
const State&,
2422 Vector& mobilityForces)
const;
2429 void calcQDot(
const State& s,
2438 void calcQDotDot(
const State& s,
2452 void addInStationForce(
const State& state,
2454 const Vec3& stationOnB,
2455 const Vec3& forceInG,
2464 void addInBodyTorque(
const State& state,
2466 const Vec3& torqueInG,
2477 void addInMobilityForce(
const State& state,
2481 Vector& mobilityForces)
const;
2511 void realizePositionKinematics(
const State& state)
const;
2525 void realizeVelocityKinematics(
const State&)
const;
2535 void realizeCompositeBodyInertias(
const State&)
const;
2550 void realizeArticulatedBodyInertias(
const State&)
const;
2580 void realizeArticulatedBodyVelocity(
const State&)
const;
2707 getMobilizerCoriolisAcceleration(
const State& state,
2767 void calcMobilizerReactionForcesUsingFreebodyMethod
2768 (
const State& state,
2778 void invalidatePositionKinematics(
const State& state)
const;
2784 bool isPositionKinematicsRealized(
const State&)
const;
2794 void invalidateVelocityKinematics(
const State& state)
const;
2801 bool isVelocityKinematicsRealized(
const State&)
const;
2806 void invalidateCompositeBodyInertias(
const State& state)
const;
2812 bool isCompositeBodyInertiasRealized(
const State&)
const;
2821 void invalidateArticulatedBodyInertias(
const State& state)
const;
2827 bool isArticulatedBodyInertiasRealized(
const State&)
const;
2836 void invalidateArticulatedBodyVelocity(
const State& state)
const;
2843 bool isArticulatedBodyVelocityRealized(
const State&)
const;
2858 int getNumParticles()
const;
2870 return getAllParticleLocations(s)[p];
2873 return getAllParticleVelocities(s)[p];
2879 updAllParticleMasses(s) = masses;
2894 return updAllParticleLocations(s)[p];
2897 return updAllParticleVelocities(s)[p];
2901 updAllParticleLocations(s)[p] = r;
2904 updAllParticleVelocities(s)[p] = v;
2908 updAllParticleLocations(s) = r;
2911 updAllParticleVelocities(s) = v;
2914 const Vector& getAllParticleMasses(
const State&)
const;
2919 return getAllParticleAccelerations(s)[p];
2935 DEPRECATED_14(
"do you really need this? see getTotalCentrifugalForces() instead")
2946 class SubtreeResults;
2950 const SimbodyMatterSubsystemRep& getRep()
const;
2951 SimbodyMatterSubsystemRep& updRep();
2966 #endif // SimTK_SIMBODY_MATTER_SUBSYSTEM_H_ PhiMatrixTranspose transpose(const PhiMatrix &phi)
Definition: SpatialAlgebra.h:720
A Subsystem is expected to be part of a larger System and to have interdependencies with other subsys...
Definition: Subsystem.h:55
Vec3 & updParticleLocation(State &s, ParticleIndex p) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2893
This is for arrays indexed by mobilized body number within a subsystem (typically the SimbodyMatterSu...
void setAllParticleMasses(State &s, const Vector &masses) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2878
This is a special type of "mobilized" body generated automatically by Simbody as a placeholder for Gr...
Definition: MobilizedBody_Ground.h:45
void calcStationJacobian(const State &state, MobilizedBodyIndex onBodyB, const Vec3 &stationPInB, Matrix &JS) const
Alternate signature for when you just have a single station task.
Definition: SimbodyMatterSubsystem.h:858
This is the top-level SimTK namespace into which all SimTK names are placed to avoid collision with o...
Definition: Assembler.h:37
This class is basically a glorified enumerated type, type-safe and range checked but permitting conve...
Definition: Stage.h:66
Vec3 & updParticleVelocity(State &s, ParticleIndex p) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2896
Vec3 calcBiasForStationJacobian(const State &state, MobilizedBodyIndex onBodyB, const Vec3 &stationPInB) const
Alternate signature for when you just have a single station task.
Definition: SimbodyMatterSubsystem.h:920
Every Simbody header and source file should include this header before any other Simbody header...
void setParticleVelocity(State &s, ParticleIndex p, const Vec3 &v) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2903
void multiplyByFrameJacobianTranspose(const State &state, MobilizedBodyIndex onBodyB, const Vec3 &originAoInB, const SpatialVec &F_GAo, Vector &f) const
Simplified signature for when you just have a single frame task.
Definition: SimbodyMatterSubsystem.h:1062
This class contains the mass, center of mass, and unit inertia matrix of a rigid body B...
Definition: MassProperties.h:85
Vec3 multiplyByStationJacobian(const State &state, MobilizedBodyIndex onBodyB, const Vec3 &stationPInB, const Vector &u) const
Alternate signature for when you just have a single station task.
Definition: SimbodyMatterSubsystem.h:747
SimTK_Real Real
This is the default compiled-in floating point type for SimTK, either float or double.
Definition: SimTKcommon/include/SimTKcommon/internal/common.h:606
This object is intended to contain all state information for a SimTK::System, except topological info...
Definition: State.h:280
This is for arrays indexed by constraint number within a subsystem (typically the SimbodyMatterSubsys...
#define DEPRECATED_14(MSG)
Definition: SimTKcommon/include/SimTKcommon/internal/common.h:289
void setAllParticleVelocities(State &s, const Vector_< Vec3 > &v) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2910
TODO: not implemented yet.
Definition: ConditionalConstraint.h:289
Includes internal headers providing declarations for the basic SimTK Core classes, including Simmatrix.
The Array_<T> container class is a plug-compatible replacement for the C++ standard template library ...
Definition: Array.h:53
SpatialVec multiplyByFrameJacobian(const State &state, MobilizedBodyIndex onBodyB, const Vec3 &originAoInB, const Vector &u) const
Simplified signature for when you just have a single frame task; see the main signature for documenta...
Definition: SimbodyMatterSubsystem.h:998
void multiplyByPq(const State &state, const Vector &qlike, Vector &PqXqlike) const
Calculate in O(n) time the product Pq*qlike where Pq is the mp X nq position (holonomic) constraint J...
Definition: SimbodyMatterSubsystem.h:1703
The job of the MultibodySystem class is to coordinate the activities of various subsystems which can ...
Definition: MultibodySystem.h:48
SimbodyMatterSubsystem & operator=(const SimbodyMatterSubsystem &ss)
Copy assignment is not very useful.
Definition: SimbodyMatterSubsystem.h:283
const Vec3 & getParticleVelocity(const State &s, ParticleIndex p) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2872
This is the matrix class intended to appear in user code for large, variable size matrices...
Definition: BigMatrix.h:168
std::ostream & operator<<(std::ostream &o, const ContactForce &f)
Definition: CompliantContactSubsystem.h:387
void calcStationJacobian(const State &state, MobilizedBodyIndex onBodyB, const Vec3 &stationPInB, RowVector_< Vec3 > &JS) const
Alternate signature for when you just have a single station task.
Definition: SimbodyMatterSubsystem.h:839
SpatialVec calcBiasForFrameJacobian(const State &state, MobilizedBodyIndex onBodyB, const Vec3 &originAoInB) const
Simplified signature for when you just have a single frame task.
Definition: SimbodyMatterSubsystem.h:1216
The physical meaning of an inertia is the distribution of a rigid body's mass about a particular poin...
Definition: MassProperties.h:82
MobilizedBody::Ground & Ground()
This is a synonym for updGround() that makes for nicer-looking examples.
Definition: SimbodyMatterSubsystem.h:188
This defines the MobilizedBody class, which associates a new body (the "child", "outboard", or "successor" body) with a mobilizer and a reference frame on an existing body (the "parent", "inboard", or "predecessor" body) that is already part of a SimbodyMatterSubsystem.
This Array_ helper class is the base class for ArrayView_ which is the base class for Array_; here we...
Definition: Array.h:51
void setAllParticleLocations(State &s, const Vector_< Vec3 > &r) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2907
#define SimTK_SIMBODY_EXPORT
Definition: Simbody/include/simbody/internal/common.h:68
SimbodyMatterSubsystem(const SimbodyMatterSubsystem &ss)
Copy constructor is not very useful.
Definition: SimbodyMatterSubsystem.h:281
A MobilizedBody is Simbody's fundamental body-and-joint object used to parameterize a system's motion...
Definition: MobilizedBody.h:168
This is the base class for all Constraint classes, which is just a handle for the underlying hidden i...
Definition: Constraint.h:66
~SimbodyMatterSubsystem()
The destructor destroys the subsystem implementation object only if this handle is the last reference...
Definition: SimbodyMatterSubsystem.h:161
Represents a variable size row vector; much less common than the column vector type Vector_...
Definition: BigMatrix.h:174
A spatial inertia contains the mass, center of mass point, and inertia matrix for a rigid body...
Definition: MassProperties.h:83
const Vec3 & getParticleAcceleration(const State &s, ParticleIndex p) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2918
An articulated body inertia (ABI) matrix P(q) contains the spatial inertia properties that a body app...
Definition: MassProperties.h:84
void calcFrameJacobian(const State &state, MobilizedBodyIndex onBodyB, const Vec3 &originAoInB, Matrix &JF) const
Simplified signature for when you just have a single frame task.
Definition: SimbodyMatterSubsystem.h:1147
This subsystem contains the bodies ("matter") in the multibody system, the mobilizers (joints) that d...
Definition: SimbodyMatterSubsystem.h:133
void setParticleLocation(State &s, ParticleIndex p, const Vec3 &r) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2900
void calcFrameJacobian(const State &state, MobilizedBodyIndex onBodyB, const Vec3 &originAoInB, RowVector_< SpatialVec > &JF) const
Simplified signature for when you just have a single frame task.
Definition: SimbodyMatterSubsystem.h:1127
const Vec3 & getParticleLocation(const State &s, ParticleIndex p) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2869
#define SimTK_PIMPL_DOWNCAST(Derived, Parent)
Similar to the above but for private implementation abstract classes, that is, abstract class hierarc...
Definition: SimTKcommon/include/SimTKcommon/internal/common.h:593
void multiplyByG(const State &state, const Vector &ulike, Vector &Gulike) const
Returns Gulike = G*ulike, the product of the mXn acceleration constraint Jacobian G and a "u-like" (m...
Definition: SimbodyMatterSubsystem.h:1503
The Mobilizer associated with each MobilizedBody, once modeled, has a specific number of generalized ...
Subsystem & operator=(const Subsystem &)
Copy assignment deletes the Subsystem::Guts object if there is one and then behaves like the copy con...