Simbody  3.3
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
SimbodyMatterSubsystem.h
Go to the documentation of this file.
1 #ifndef SimTK_SIMBODY_MATTER_SUBSYSTEM_H_
2 #define SimTK_SIMBODY_MATTER_SUBSYSTEM_H_
3 
4 /* -------------------------------------------------------------------------- *
5  * Simbody(tm) *
6  * -------------------------------------------------------------------------- *
7  * This is part of the SimTK biosimulation toolkit originating from *
8  * Simbios, the NIH National Center for Physics-Based Simulation of *
9  * Biological Structures at Stanford, funded under the NIH Roadmap for *
10  * Medical Research, grant U54 GM072970. See https://simtk.org/home/simbody. *
11  * *
12  * Portions copyright (c) 2006-12 Stanford University and the Authors. *
13  * Authors: Michael Sherman *
14  * Contributors: Paul Mitiguy *
15  * *
16  * Licensed under the Apache License, Version 2.0 (the "License"); you may *
17  * not use this file except in compliance with the License. You may obtain a *
18  * copy of the License at http://www.apache.org/licenses/LICENSE-2.0. *
19  * *
20  * Unless required by applicable law or agreed to in writing, software *
21  * distributed under the License is distributed on an "AS IS" BASIS, *
22  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
23  * See the License for the specific language governing permissions and *
24  * limitations under the License. *
25  * -------------------------------------------------------------------------- */
26 
27 #include "SimTKcommon.h"
30 
31 #include <cassert>
32 #include <vector>
33 #include <iostream>
34 
35 class SimbodyMatterSubsystemRep;
36 
37 namespace SimTK {
38 
39 class MobilizedBody;
40 class MultibodySystem;
41 class Constraint;
42 
131 public:
132 
133 //==============================================================================
158 ~SimbodyMatterSubsystem() {} // invokes ~Subsystem()
159 
164 const MobilizedBody& getMobilizedBody(MobilizedBodyIndex) const;
165 
170 MobilizedBody& updMobilizedBody(MobilizedBodyIndex);
171 
174 const MobilizedBody::Ground& getGround() const;
178 MobilizedBody::Ground& updGround();
185 MobilizedBody::Ground& Ground() {return updGround();}
186 
187 
191 const Constraint& getConstraint(ConstraintIndex) const;
192 
196 Constraint& updConstraint(ConstraintIndex);
197 
201 void setShowDefaultGeometry(bool show);
204 bool getShowDefaultGeometry() const;
205 
216 int getNumBodies() const;
217 
221 int getNumConstraints() const;
222 
225 int getNumMobilities() const;
226 
229 int getTotalQAlloc() const;
230 
234 int getTotalMultAlloc() const;
235 
236 
249 MobilizedBodyIndex adoptMobilizedBody(MobilizedBodyIndex parent,
250  MobilizedBody& child);
251 
262 ConstraintIndex adoptConstraint(Constraint&);
263 
268 { Subsystem::operator=(ss); return *this; }
269 
270 
271 //==============================================================================
286 void setUseEulerAngles(State& state, bool useEulerAngles) const;
287 
290 bool getUseEulerAngles (const State& state) const;
291 
296 int getNumQuaternionsInUse(const State& state) const;
297 
302 bool isUsingQuaternion(const State& state, MobilizedBodyIndex mobodIx) const;
308 QuaternionPoolIndex getQuaternionPoolIndex(const State& state,
309  MobilizedBodyIndex mobodIx) const;
310 
317 void setConstraintIsDisabled(State& state,
318  ConstraintIndex constraintIx,
319  bool shouldDisableConstraint) const;
320 
324 bool isConstraintDisabled(const State&, ConstraintIndex constraint) const;
325 
332 void convertToEulerAngles(const State& inputState, State& outputState) const;
333 
340 void convertToQuaternions(const State& inputState, State& outputState) const;
341 
345 //==============================================================================
359 Real calcSystemMass(const State& s) const;
360 
365 Vec3 calcSystemMassCenterLocationInGround(const State& s) const;
366 
371 MassProperties calcSystemMassPropertiesInGround(const State& s) const;
372 
377 Inertia calcSystemCentralInertiaInGround(const State& s) const;
378 
383 Vec3 calcSystemMassCenterVelocityInGround(const State& s) const;
384 
389 Vec3 calcSystemMassCenterAccelerationInGround(const State& s) const;
390 
397 SpatialVec calcSystemMomentumAboutGroundOrigin(const State& s) const;
398 
406 SpatialVec calcSystemCentralMomentum(const State& s) const;
407 
412 Real calcKineticEnergy(const State& state) const;
415 //==============================================================================
528 void multiplyBySystemJacobian( const State& state,
529  const Vector& u,
530  Vector_<SpatialVec>& Ju) const;
531 
559 void calcBiasForSystemJacobian(const State& state,
560  Vector_<SpatialVec>& JDotu) const;
561 
562 
566 void calcBiasForSystemJacobian(const State& state,
567  Vector& JDotu) const;
568 
620 void multiplyBySystemJacobianTranspose( const State& state,
621  const Vector_<SpatialVec>& F_G,
622  Vector& f) const;
623 
624 
657 void calcSystemJacobian(const State& state,
658  Matrix_<SpatialVec>& J_G) const; // nb X nu
659 
664 void calcSystemJacobian(const State& state,
665  Matrix& J_G) const; // 6 nb X nu
666 
667 
713 void multiplyByStationJacobian(const State& state,
714  const Array_<MobilizedBodyIndex>& onBodyB,
715  const Array_<Vec3>& stationPInB,
716  const Vector& u,
717  Vector_<Vec3>& JSu) const;
718 
722  MobilizedBodyIndex onBodyB,
723  const Vec3& stationPInB,
724  const Vector& u) const
725 {
726  ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
727  ArrayViewConst_<Vec3> stations(&stationPInB, &stationPInB+1);
728  Vector_<Vec3> JSu(1);
729  multiplyByStationJacobian(state, bodies, stations, u, JSu);
730  return JSu[0];
731 }
732 
733 
746 void multiplyByStationJacobianTranspose
747  (const State& state,
748  const Array_<MobilizedBodyIndex>& onBodyB,
749  const Array_<Vec3>& stationPInB,
750  const Vector_<Vec3>& f_GP,
751  Vector& f) const;
752 
754 void multiplyByStationJacobianTranspose
755  (const State& state,
756  MobilizedBodyIndex onBodyB,
757  const Vec3& stationPInB,
758  const Vec3& f_GP,
759  Vector& f) const
760 {
761  ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
762  ArrayViewConst_<Vec3> stations(&stationPInB, &stationPInB+1);
763  Vector_<Vec3> forces(1, f_GP);
764  multiplyByStationJacobianTranspose(state, bodies, stations, forces, f);
765 }
766 
807 void calcStationJacobian(const State& state,
808  const Array_<MobilizedBodyIndex>& onBodyB,
809  const Array_<Vec3>& stationPInB,
810  Matrix_<Vec3>& JS) const;
811 
813 void calcStationJacobian(const State& state,
814  MobilizedBodyIndex onBodyB,
815  const Vec3& stationPInB,
816  RowVector_<Vec3>& JS) const
817 {
818  ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
819  ArrayViewConst_<Vec3> stations(&stationPInB, &stationPInB+1);
820  calcStationJacobian(state, bodies, stations, JS);
821 }
822 
826 void calcStationJacobian(const State& state,
827  const Array_<MobilizedBodyIndex>& onBodyB,
828  const Array_<Vec3>& stationPInB,
829  Matrix& JS) const;
830 
832 void calcStationJacobian(const State& state,
833  MobilizedBodyIndex onBodyB,
834  const Vec3& stationPInB,
835  Matrix& JS) const
836 {
837  ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
838  ArrayViewConst_<Vec3> stations(&stationPInB, &stationPInB+1);
839  calcStationJacobian(state, bodies, stations, JS);
840 }
841 
842 
879 void calcBiasForStationJacobian(const State& state,
880  const Array_<MobilizedBodyIndex>& onBodyB,
881  const Array_<Vec3>& stationPInB,
882  Vector_<Vec3>& JSDotu) const;
883 
887 void calcBiasForStationJacobian(const State& state,
888  const Array_<MobilizedBodyIndex>& onBodyB,
889  const Array_<Vec3>& stationPInB,
890  Vector& JSDotu) const;
891 
895  MobilizedBodyIndex onBodyB,
896  const Vec3& stationPInB) const
897 {
898  ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
899  ArrayViewConst_<Vec3> stations(&stationPInB, &stationPInB+1);
900  Vector_<Vec3> JSDotu(1);
901  calcBiasForStationJacobian(state, bodies, stations, JSDotu);
902  return JSDotu[0];
903 }
904 
905 
962 void multiplyByFrameJacobian
963  (const State& state,
964  const Array_<MobilizedBodyIndex>& onBodyB,
965  const Array_<Vec3>& originAoInB,
966  const Vector& u,
967  Vector_<SpatialVec>& JFu) const;
968 
973  MobilizedBodyIndex onBodyB,
974  const Vec3& originAoInB,
975  const Vector& u) const
976 {
977  ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
978  ArrayViewConst_<Vec3> stations(&originAoInB, &originAoInB+1);
979  Vector_<SpatialVec> JFu(1);
980  multiplyByFrameJacobian(state, bodies, stations, u, JFu);
981  return JFu[0];
982 }
983 
984 
1027 void multiplyByFrameJacobianTranspose
1028  (const State& state,
1029  const Array_<MobilizedBodyIndex>& onBodyB,
1030  const Array_<Vec3>& originAoInB,
1031  const Vector_<SpatialVec>& F_GAo,
1032  Vector& f) const;
1033 
1037  MobilizedBodyIndex onBodyB,
1038  const Vec3& originAoInB,
1039  const SpatialVec& F_GAo,
1040  Vector& f) const
1041 {
1042  ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
1043  ArrayViewConst_<Vec3> stations(&originAoInB, &originAoInB+1);
1044  const Vector_<SpatialVec> forces(1, F_GAo);
1045  multiplyByFrameJacobianTranspose(state, bodies, stations, forces, f);
1046 }
1047 
1048 
1049 
1094 void calcFrameJacobian(const State& state,
1095  const Array_<MobilizedBodyIndex>& onBodyB,
1096  const Array_<Vec3>& originAoInB,
1097  Matrix_<SpatialVec>& JF) const;
1098 
1101 void calcFrameJacobian(const State& state,
1102  MobilizedBodyIndex onBodyB,
1103  const Vec3& originAoInB,
1104  RowVector_<SpatialVec>& JF) const
1105 {
1106  ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
1107  ArrayViewConst_<Vec3> stations(&originAoInB, &originAoInB+1);
1108  calcFrameJacobian(state, bodies, stations, JF);
1109 }
1110 
1114 void calcFrameJacobian(const State& state,
1115  const Array_<MobilizedBodyIndex>& onBodyB,
1116  const Array_<Vec3>& originAoInB,
1117  Matrix& JF) const;
1118 
1121 void calcFrameJacobian(const State& state,
1122  MobilizedBodyIndex onBodyB,
1123  const Vec3& originAoInB,
1124  Matrix& JF) const
1125 {
1126  ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
1127  ArrayViewConst_<Vec3> stations(&originAoInB, &originAoInB+1);
1128  calcFrameJacobian(state, bodies, stations, JF);
1129 }
1130 
1173 void calcBiasForFrameJacobian
1174  (const State& state,
1175  const Array_<MobilizedBodyIndex>& onBodyB,
1176  const Array_<Vec3>& originAoInB,
1177  Vector_<SpatialVec>& JFDotu) const;
1178 
1182 void calcBiasForFrameJacobian(const State& state,
1183  const Array_<MobilizedBodyIndex>& onBodyB,
1184  const Array_<Vec3>& originAoInB,
1185  Vector& JFDotu) const;
1186 
1191  MobilizedBodyIndex onBodyB,
1192  const Vec3& originAoInB) const
1193 {
1194  ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
1195  ArrayViewConst_<Vec3> stations(&originAoInB, &originAoInB+1);
1196  Vector_<SpatialVec> JFDotu(1);
1197  calcBiasForFrameJacobian(state, bodies, stations, JFDotu);
1198  return JFDotu[0];
1199 }
1200 
1203 //==============================================================================
1236 void multiplyByM(const State& state, const Vector& a, Vector& Ma) const;
1237 
1317 void multiplyByMInv(const State& state,
1318  const Vector& v,
1319  Vector& MinvV) const;
1320 
1330 void calcM(const State&, Matrix& M) const;
1331 
1345 void calcMInv(const State&, Matrix& MInv) const;
1346 
1391 void calcProjectedMInv(const State& s,
1392  Matrix& GMInvGt) const;
1393 
1438 void solveForConstraintImpulses(const State& state,
1439  const Vector& deltaV,
1440  Vector& impulse) const;
1441 
1442 
1466 void multiplyByG(const State& state,
1467  const Vector& ulike,
1468  Vector& Gulike) const {
1469  Vector bias;
1470  calcBiasForMultiplyByG(state, bias);
1471  multiplyByG(state, ulike, bias, Gulike);
1472 }
1473 
1474 
1478 void multiplyByG(const State& state,
1479  const Vector& ulike,
1480  const Vector& bias,
1481  Vector& Gulike) const;
1482 
1508 void calcBiasForMultiplyByG(const State& state,
1509  Vector& bias) const;
1510 
1524 void calcG(const State& state, Matrix& G) const;
1525 
1526 
1561 void calcBiasForAccelerationConstraints(const State& state,
1562  Vector& bias) const;
1563 
1564 
1598 void multiplyByGTranspose(const State& state,
1599  const Vector& lambda,
1600  Vector& f) const;
1601 
1613 void calcGTranspose(const State&, Matrix& Gt) const;
1614 
1615 
1666 void multiplyByPq(const State& state,
1667  const Vector& qlike,
1668  Vector& PqXqlike) const {
1669  Vector biasp;
1670  calcBiasForMultiplyByPq(state, biasp);
1671  multiplyByPq(state, qlike, biasp, PqXqlike);
1672 }
1673 
1674 
1678 void multiplyByPq(const State& state,
1679  const Vector& qlike,
1680  const Vector& biasp,
1681  Vector& PqXqlike) const;
1682 
1699 void calcBiasForMultiplyByPq(const State& state,
1700  Vector& biasp) const;
1701 
1729 void calcPq(const State& state, Matrix& Pq) const;
1730 
1731 
1764 void multiplyByPqTranspose(const State& state,
1765  const Vector& lambdap,
1766  Vector& f) const;
1767 
1795 void calcPqTranspose(const State& state, Matrix& Pqt) const;
1796 
1813 void calcP(const State& state, Matrix& P) const;
1814 
1818 void calcPt(const State& state, Matrix& Pt) const;
1819 
1820 
1829 void multiplyByN(const State& s, bool transpose,
1830  const Vector& in, Vector& out) const;
1831 
1840 void multiplyByNInv(const State& s, bool transpose,
1841  const Vector& in, Vector& out) const;
1842 
1852 void multiplyByNDot(const State& s, bool transpose,
1853  const Vector& in, Vector& out) const;
1854 
1858 //==============================================================================
1919 void calcAcceleration
1920  (const State& state,
1921  const Vector& appliedMobilityForces,
1922  const Vector_<SpatialVec>& appliedBodyForces,
1923  Vector& udot, // output only; no prescribed motions
1924  Vector_<SpatialVec>& A_GB) const;
1925 
1949 void calcAccelerationIgnoringConstraints
1950  (const State& state,
1951  const Vector& appliedMobilityForces,
1952  const Vector_<SpatialVec>& appliedBodyForces,
1953  Vector& udot,
1954  Vector_<SpatialVec>& A_GB) const;
1955 
1956 
1957 
2012 void calcResidualForceIgnoringConstraints
2013  (const State& state,
2014  const Vector& appliedMobilityForces,
2015  const Vector_<SpatialVec>& appliedBodyForces,
2016  const Vector& knownUdot,
2017  Vector& residualMobilityForces) const;
2018 
2019 
2082 void calcResidualForce
2083  (const State& state,
2084  const Vector& appliedMobilityForces,
2085  const Vector_<SpatialVec>& appliedBodyForces,
2086  const Vector& knownUdot,
2087  const Vector& knownLambda,
2088  Vector& residualMobilityForces) const;
2089 
2090 
2101 void calcCompositeBodyInertias(const State& state,
2103 
2104 
2105 
2143 void calcBodyAccelerationFromUDot(const State& state,
2144  const Vector& knownUDot,
2145  Vector_<SpatialVec>& A_GB) const;
2146 
2147 
2170 void calcConstraintForcesFromMultipliers
2171  (const State& state,
2172  const Vector& multipliers,
2173  Vector_<SpatialVec>& bodyForcesInG,
2174  Vector& mobilityForces) const;
2175 
2258 void calcMobilizerReactionForces
2259  (const State& state,
2260  Vector_<SpatialVec>& forcesAtMInG) const;
2261 
2268 const Vector& getMotionMultipliers(const State& state) const;
2269 
2283 Vector calcMotionErrors(const State& state, const Stage& stage) const;
2284 
2290 void findMotionForces
2291  (const State& state,
2292  Vector& mobilityForces) const;
2293 
2300 const Vector& getConstraintMultipliers(const State& state) const;
2301 
2306 void findConstraintForces
2307  (const State& state,
2308  Vector_<SpatialVec>& bodyForcesInG,
2309  Vector& mobilityForces) const;
2310 
2326 Real calcMotionPower(const State& state) const;
2327 
2354 Real calcConstraintPower(const State& state) const;
2355 
2361 void calcTreeEquivalentMobilityForces(const State&,
2362  const Vector_<SpatialVec>& bodyForces,
2363  Vector& mobilityForces) const;
2364 
2365 
2370 void calcQDot(const State& s,
2371  const Vector& u,
2372  Vector& qdot) const;
2373 
2379 void calcQDotDot(const State& s,
2380  const Vector& udot,
2381  Vector& qdotdot) const;
2382 
2393 void addInStationForce(const State& state,
2394  MobilizedBodyIndex bodyB,
2395  const Vec3& stationOnB,
2396  const Vec3& forceInG,
2397  Vector_<SpatialVec>& bodyForcesInG) const;
2398 
2405 void addInBodyTorque(const State& state,
2406  MobilizedBodyIndex mobodIx,
2407  const Vec3& torqueInG,
2408  Vector_<SpatialVec>& bodyForcesInG) const;
2409 
2418 void addInMobilityForce(const State& state,
2419  MobilizedBodyIndex mobodIx,
2420  MobilizerUIndex which,
2421  Real f,
2422  Vector& mobilityForces) const;
2427 //==============================================================================
2442  // POSITION STAGE realizations //
2443 
2451 void realizeCompositeBodyInertias(const State&) const;
2452 
2461 void realizeArticulatedBodyInertias(const State&) const;
2462 
2463 
2464  // INSTANCE STAGE responses //
2465 
2466 const Array_<QIndex>& getFreeQIndex(const State& state) const;
2467 const Array_<UIndex>& getFreeUIndex(const State& state) const;
2468 const Array_<UIndex>& getFreeUDotIndex(const State& state) const;
2469 const Array_<UIndex>& getKnownUDotIndex(const State& state) const;
2470 void packFreeQ
2471  (const State& s, const Vector& allQ, Vector& packedFreeQ) const;
2472 void unpackFreeQ
2473  (const State& s, const Vector& packedFreeQ, Vector& unpackedFreeQ) const;
2474 void packFreeU
2475  (const State& s, const Vector& allU, Vector& packedFreeU) const;
2476 void unpackFreeU
2477  (const State& s, const Vector& packedFreeU, Vector& unpackedFreeU) const;
2478 
2479 
2480  // POSITION STAGE responses //
2481 
2491 const SpatialInertia&
2492 getCompositeBodyInertia(const State& state, MobilizedBodyIndex mbx) const;
2493 
2504 const ArticulatedInertia&
2505 getArticulatedBodyInertia(const State& state, MobilizedBodyIndex mbx) const;
2506 
2507 
2508  // VELOCITY STAGE responses //
2509 
2514 const SpatialVec&
2515 getGyroscopicForce(const State& state, MobilizedBodyIndex mbx) const;
2516 
2522 const SpatialVec&
2523 getMobilizerCoriolisAcceleration(const State& state,
2524  MobilizedBodyIndex mbx) const;
2525 
2534 const SpatialVec&
2535 getTotalCoriolisAcceleration(const State& state, MobilizedBodyIndex mbx) const;
2536 
2537 
2538  // DYNAMICS STAGE responses //
2539 
2546 const SpatialVec&
2547 getMobilizerCentrifugalForces(const State& state, MobilizedBodyIndex mbx) const;
2548 
2554 const SpatialVec&
2555 getTotalCentrifugalForces(const State& state, MobilizedBodyIndex mbx) const;
2560 //==============================================================================
2591 void calcMobilizerReactionForcesUsingFreebodyMethod
2592  (const State& state,
2593  Vector_<SpatialVec>& forcesAtMInG) const;
2597 //==============================================================================
2608 int getNumParticles() const;
2610 
2611 // The generalized coordinates for a particle are always the three measure numbers
2612 // (x,y,z) of the particle's Ground-relative Cartesian location vector. The generalized
2613 // speeds are always the three corresponding measure numbers of the particle's
2614 // Ground-relative Cartesian velocity. The generalized applied forces are
2615 // always the three measure numbers of a Ground-relative force vector.
2616 const Vector_<Vec3>& getAllParticleLocations (const State&) const;
2617 const Vector_<Vec3>& getAllParticleVelocities (const State&) const;
2618 
2619 const Vec3& getParticleLocation(const State& s, ParticleIndex p) const {
2620  return getAllParticleLocations(s)[p];
2621 }
2622 const Vec3& getParticleVelocity(const State& s, ParticleIndex p) const {
2623  return getAllParticleVelocities(s)[p];
2624 }
2625 
2626 Vector& updAllParticleMasses(State& s) const;
2627 
2628 void setAllParticleMasses(State& s, const Vector& masses) const {
2629  updAllParticleMasses(s) = masses;
2630 }
2631 
2632 // Note that particle generalized coordinates, speeds, and applied forces
2633 // are defined to be the particle Cartesian locations, velocities, and
2634 // applied force vectors, so can be set directly at Stage::Model or higher.
2635 
2636 // These are the only routines that must be provided by the concrete MatterSubsystem.
2637 Vector_<Vec3>& updAllParticleLocations(State&) const;
2638 Vector_<Vec3>& updAllParticleVelocities(State&) const;
2639 
2640 // The following inline routines are provided by the generic MatterSubsystem
2641 // class for convenience.
2642 
2643 Vec3& updParticleLocation(State& s, ParticleIndex p) const {
2644  return updAllParticleLocations(s)[p];
2645 }
2646 Vec3& updParticleVelocity(State& s, ParticleIndex p) const {
2647  return updAllParticleVelocities(s)[p];
2648 }
2649 
2650 void setParticleLocation(State& s, ParticleIndex p, const Vec3& r) const {
2651  updAllParticleLocations(s)[p] = r;
2652 }
2653 void setParticleVelocity(State& s, ParticleIndex p, const Vec3& v) const {
2654  updAllParticleVelocities(s)[p] = v;
2655 }
2656 
2657 void setAllParticleLocations(State& s, const Vector_<Vec3>& r) const {
2658  updAllParticleLocations(s) = r;
2659 }
2661  updAllParticleVelocities(s) = v;
2662 }
2663 
2664 const Vector& getAllParticleMasses(const State&) const;
2665 
2666 const Vector_<Vec3>& getAllParticleAccelerations(const State&) const;
2667 
2668 const Vec3& getParticleAcceleration(const State& s, ParticleIndex p) const {
2669  return getAllParticleAccelerations(s)[p];
2670 }
2673 //==============================================================================
2682 private:
2685 void calcSpatialKinematicsFromInternal(const State& state,
2686  const Vector& u,
2687  Vector_<SpatialVec>& Ju) const
2688 { multiplyBySystemJacobian(state,u,Ju); }
2689 
2692 void calcInternalGradientFromSpatial(const State& state,
2693  const Vector_<SpatialVec>& F_G,
2694  Vector& f) const
2695 { multiplyBySystemJacobianTranspose(state, F_G, f); }
2696 
2699 void calcMV(const State& state, const Vector& v, Vector& MV) const
2700 { multiplyByM(state,v,MV); }
2701 
2704 void calcMInverseV(const State& state,
2705  const Vector& v,
2706  Vector& MinvV) const
2707 { multiplyByMInv(state,v,MinvV); }
2708 
2711 void calcPNInv(const State& state, Matrix& PNInv) const;
2712 
2715 void calcGt(const State&, Matrix& Gt) const;
2716 
2717 
2721 //==============================================================================
2722 // Bookkeeping methods and internal types -- hide from Doxygen
2724 public:
2725 class Subtree; // used for working with a connected subgraph of the MobilizedBody tree
2726 class SubtreeResults;
2727 
2728 
2729 SimTK_PIMPL_DOWNCAST(SimbodyMatterSubsystem, Subsystem);
2730 const SimbodyMatterSubsystemRep& getRep() const;
2731 SimbodyMatterSubsystemRep& updRep();
2734 private:
2735 };
2736 
2740 SimTK_SIMBODY_EXPORT std::ostream&
2741 operator<<(std::ostream&, const SimbodyMatterSubsystem&);
2742 
2743 
2744 } // namespace SimTK
2745 
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 &)