1 #ifndef SimTK_SIMBODY_MATTER_SUBSYSTEM_H_
2 #define SimTK_SIMBODY_MATTER_SUBSYSTEM_H_
35 class SimbodyMatterSubsystemRep;
40 class MultibodySystem;
201 void setShowDefaultGeometry(
bool show);
204 bool getShowDefaultGeometry()
const;
216 int getNumBodies()
const;
221 int getNumConstraints()
const;
225 int getNumMobilities()
const;
229 int getTotalQAlloc()
const;
234 int getTotalMultAlloc()
const;
286 void setUseEulerAngles(
State& state,
bool useEulerAngles)
const;
290 bool getUseEulerAngles (
const State& state)
const;
296 int getNumQuaternionsInUse(
const State& state)
const;
308 QuaternionPoolIndex getQuaternionPoolIndex(
const State& state,
317 void setConstraintIsDisabled(
State& state,
319 bool shouldDisableConstraint)
const;
332 void convertToEulerAngles(
const State& inputState,
State& outputState)
const;
340 void convertToQuaternions(
const State& inputState,
State& outputState)
const;
359 Real calcSystemMass(
const State& s)
const;
365 Vec3 calcSystemMassCenterLocationInGround(
const State& s)
const;
377 Inertia calcSystemCentralInertiaInGround(
const State& s)
const;
383 Vec3 calcSystemMassCenterVelocityInGround(
const State& s)
const;
389 Vec3 calcSystemMassCenterAccelerationInGround(
const State& s)
const;
412 Real calcKineticEnergy(
const State& state)
const;
528 void multiplyBySystemJacobian(
const State& state,
559 void calcBiasForSystemJacobian(
const State& state,
566 void calcBiasForSystemJacobian(
const State& state,
620 void multiplyBySystemJacobianTranspose(
const State& state,
657 void calcSystemJacobian(
const State& state,
664 void calcSystemJacobian(
const State& state,
713 void multiplyByStationJacobian(
const State& state,
723 const Vec3& stationPInB,
729 multiplyByStationJacobian(state, bodies, stations, u, JSu);
746 void multiplyByStationJacobianTranspose
754 void multiplyByStationJacobianTranspose
757 const Vec3& stationPInB,
764 multiplyByStationJacobianTranspose(state, bodies, stations, forces, f);
807 void calcStationJacobian(
const State& state,
815 const Vec3& stationPInB,
820 calcStationJacobian(state, bodies, stations, JS);
826 void calcStationJacobian(
const State& state,
834 const Vec3& stationPInB,
839 calcStationJacobian(state, bodies, stations, JS);
879 void calcBiasForStationJacobian(
const State& state,
887 void calcBiasForStationJacobian(
const State& state,
896 const Vec3& stationPInB)
const
901 calcBiasForStationJacobian(state, bodies, stations, JSDotu);
962 void multiplyByFrameJacobian
974 const Vec3& originAoInB,
980 multiplyByFrameJacobian(state, bodies, stations, u, JFu);
1027 void multiplyByFrameJacobianTranspose
1028 (
const State& state,
1038 const Vec3& originAoInB,
1045 multiplyByFrameJacobianTranspose(state, bodies, stations, forces, f);
1094 void calcFrameJacobian(
const State& state,
1103 const Vec3& originAoInB,
1108 calcFrameJacobian(state, bodies, stations, JF);
1114 void calcFrameJacobian(
const State& state,
1123 const Vec3& originAoInB,
1128 calcFrameJacobian(state, bodies, stations, JF);
1173 void calcBiasForFrameJacobian
1174 (
const State& state,
1182 void calcBiasForFrameJacobian(
const State& state,
1192 const Vec3& originAoInB)
const
1197 calcBiasForFrameJacobian(state, bodies, stations, JFDotu);
1317 void multiplyByMInv(
const State& state,
1391 void calcProjectedMInv(
const State& s,
1438 void solveForConstraintImpulses(
const State& state,
1470 calcBiasForMultiplyByG(state, bias);
1471 multiplyByG(state, ulike, bias, Gulike);
1478 void multiplyByG(
const State& state,
1508 void calcBiasForMultiplyByG(
const State& state,
1561 void calcBiasForAccelerationConstraints(
const State& state,
1598 void multiplyByGTranspose(
const State& state,
1613 void calcGTranspose(
const State&,
Matrix& Gt)
const;
1668 Vector& PqXqlike)
const {
1670 calcBiasForMultiplyByPq(state, biasp);
1671 multiplyByPq(state, qlike, biasp, PqXqlike);
1678 void multiplyByPq(
const State& state,
1699 void calcBiasForMultiplyByPq(
const State& state,
1729 void calcPq(
const State& state,
Matrix& Pq)
const;
1764 void multiplyByPqTranspose(
const State& state,
1795 void calcPqTranspose(
const State& state,
Matrix& Pqt)
const;
1818 void calcPt(
const State& state,
Matrix& Pt)
const;
1919 void calcAcceleration
1920 (
const State& state,
1921 const Vector& appliedMobilityForces,
1949 void calcAccelerationIgnoringConstraints
1950 (
const State& state,
1951 const Vector& appliedMobilityForces,
2012 void calcResidualForceIgnoringConstraints
2013 (
const State& state,
2014 const Vector& appliedMobilityForces,
2017 Vector& residualMobilityForces)
const;
2082 void calcResidualForce
2083 (
const State& state,
2084 const Vector& appliedMobilityForces,
2087 const Vector& knownLambda,
2088 Vector& residualMobilityForces)
const;
2101 void calcCompositeBodyInertias(
const State& state,
2143 void calcBodyAccelerationFromUDot(
const State& state,
2170 void calcConstraintForcesFromMultipliers
2171 (
const State& state,
2172 const Vector& multipliers,
2174 Vector& mobilityForces)
const;
2258 void calcMobilizerReactionForces
2259 (
const State& state,
2268 const Vector& getMotionMultipliers(
const State& state)
const;
2290 void findMotionForces
2291 (
const State& state,
2292 Vector& mobilityForces)
const;
2300 const Vector& getConstraintMultipliers(
const State& state)
const;
2306 void findConstraintForces
2307 (
const State& state,
2309 Vector& mobilityForces)
const;
2326 Real calcMotionPower(
const State& state)
const;
2354 Real calcConstraintPower(
const State& state)
const;
2361 void calcTreeEquivalentMobilityForces(
const State&,
2363 Vector& mobilityForces)
const;
2370 void calcQDot(
const State& s,
2379 void calcQDotDot(
const State& s,
2393 void addInStationForce(
const State& state,
2395 const Vec3& stationOnB,
2396 const Vec3& forceInG,
2405 void addInBodyTorque(
const State& state,
2407 const Vec3& torqueInG,
2418 void addInMobilityForce(
const State& state,
2422 Vector& mobilityForces)
const;
2451 void realizeCompositeBodyInertias(
const State&)
const;
2461 void realizeArticulatedBodyInertias(
const State&)
const;
2523 getMobilizerCoriolisAcceleration(
const State& state,
2591 void calcMobilizerReactionForcesUsingFreebodyMethod
2592 (
const State& state,
2608 int getNumParticles()
const;
2620 return getAllParticleLocations(s)[p];
2623 return getAllParticleVelocities(s)[p];
2629 updAllParticleMasses(s) = masses;
2644 return updAllParticleLocations(s)[p];
2647 return updAllParticleVelocities(s)[p];
2651 updAllParticleLocations(s)[p] = r;
2654 updAllParticleVelocities(s)[p] = v;
2658 updAllParticleLocations(s) = r;
2661 updAllParticleVelocities(s) = v;
2664 const Vector& getAllParticleMasses(
const State&)
const;
2669 return getAllParticleAccelerations(s)[p];
2685 void calcSpatialKinematicsFromInternal(
const State& state,
2688 { multiplyBySystemJacobian(state,u,Ju); }
2692 void calcInternalGradientFromSpatial(
const State& state,
2693 const Vector_<SpatialVec>& F_G,
2695 { multiplyBySystemJacobianTranspose(state, F_G, f); }
2699 void calcMV(
const State& state,
const Vector& v,
Vector& MV)
const
2700 { multiplyByM(state,v,MV); }
2704 void calcMInverseV(
const State& state,
2707 { multiplyByMInv(state,v,MinvV); }
2711 void calcPNInv(
const State& state,
Matrix& PNInv)
const;
2715 void calcGt(
const State&,
Matrix& Gt)
const;
2726 class SubtreeResults;
2729 SimTK_PIMPL_DOWNCAST(SimbodyMatterSubsystem, Subsystem);
2730 const SimbodyMatterSubsystemRep& getRep()
const;
2731 SimbodyMatterSubsystemRep& updRep();
2741 operator<<(std::ostream&,
const SimbodyMatterSubsystem&);
2746 #endif // SimTK_SIMBODY_MATTER_SUBSYSTEM_H_
PhiMatrixTranspose transpose(const PhiMatrix &phi)
Definition: SpatialAlgebra.h:720
The abstract parent of all Subsystems.
Definition: Subsystem.h:61
Vec3 & updParticleLocation(State &s, ParticleIndex p) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2643
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:2628
This is a special type of "mobilized" body generated automatically by Simbody as a placeholder for ...
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:832
Matrix_< Real > Matrix
Read fixed-size VectorView from input stream.
Definition: BigMatrix.h:3569
This class is basically a glorified enumerated type, type-safe and range checked but permitting conve...
Definition: Stage.h:50
Vec3 & updParticleVelocity(State &s, ParticleIndex p) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2646
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:894
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:2653
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:1036
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:721
This is the handle class for the hidden State implementation.
Definition: State.h:264
This is for arrays indexed by constraint number within a subsystem (typically the SimbodyMatterSubsys...
void setAllParticleVelocities(State &s, const Vector_< Vec3 > &v) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2660
Includes internal headers providing declarations for the basic SimTK Core classes, including Simmatrix.
Vector_< Real > Vector
Read fixed-size VectorView from input stream.
Definition: BigMatrix.h:3541
The SimTK::Array_<T> container class is a plug-compatible replacement for the C++ standard template l...
Definition: Array.h:50
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:972
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:1666
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:267
const Vec3 & getParticleVelocity(const State &s, ParticleIndex p) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2622
This is the Matrix class intended to appear in user code.
Definition: BigMatrix.h:181
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:813
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:1190
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:185
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:48
void setAllParticleLocations(State &s, const Vector_< Vec3 > &r) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2657
#define SimTK_SIMBODY_EXPORT
Definition: Simbody/include/simbody/internal/common.h:72
SimbodyMatterSubsystem(const SimbodyMatterSubsystem &ss)
Copy constructor is not very useful.
Definition: SimbodyMatterSubsystem.h:265
A MobilizedBody is Simbody's fundamental body-and-joint object used to parameterize a system's motion...
Definition: MobilizedBody.h:167
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:158
RowVectors are much less common than Vectors.
Definition: BigMatrix.h:191
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:2668
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:1121
This subsystem contains the bodies ("matter") in the multibody system, the mobilizers (joints) that d...
Definition: SimbodyMatterSubsystem.h:130
void setParticleLocation(State &s, ParticleIndex p, const Vec3 &r) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2650
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:1101
const Vec3 & getParticleLocation(const State &s, ParticleIndex p) const
TODO: total number of particles.
Definition: SimbodyMatterSubsystem.h:2619
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:1466
The Mobilizer associated with each MobilizedBody, once modeled, has a specific number of generalized ...
Subsystem & operator=(const Subsystem &)