1 #ifndef SimTK_SIMBODY_TREE_STATE_H_
2 #define SimTK_SIMBODY_TREE_STATE_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) 2005-12 Stanford University and the Authors.        *
13  * Authors: Michael Sherman                                                   *
14  * Contributors:                                                              *
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 /* This file contains the classes which define the SimbodyMatterSubsystem State,
28 that is, everything that can be changed in a SimbodyMatterSubsystem after
29 construction.
30 
31 State variables and computation results are organized into stages:
32    Stage::Empty         virginal state just allocated
33    Stage::Topology      Stored in SimbodyMatterSubsystem object (construction)
34   ---------------------------------------------------------
35    Stage::Model         Stored in the State object
36    Stage::Instance
37    Stage::Time
38    Stage::Position
39    Stage::Velocity
40    Stage::Dynamics      calculate forces
41    Stage::Acceleration  response to forces in the state
42   ---------------------------------------------------------
43    Stage::Report        only used when outputting something
44 
45 Construction proceeds until all the bodies and constraints have been specified.
46 After that, realizeTopology() is called. Construction-related calculations are
47 performed leading to values which are stored in the SimbodyMatterSubsystem
48 object, NOT in the State (e.g., total number of bodies). At the same time, an
49 initial state is built, with space allocated for the state variables that will
50 be needed by the next stage (Stage::Model),and these are assigned default
51 values. Then the stage in the SimbodyMatterSubsystem and in the initial state
52 is set to "Topology".
53 
54 After that, values for Model stage variables can be set in the State.
55 When that's done we call realizeModel(), which evaluates the Model states
56 putting the values into state cache entries allocated for the purpose. Then
57 all remaining state variables are allocated, and set to their default values.
58 All defaults must be computable knowing only the Model stage values.
59 Then the stage is advanced to Stage::Model.
60 
61 This continues through all the stages, with realizeWhatever() expecting to
62 receive a state evaluated to stage Whatever-1 equipped with values for stage
63 Whatever so that it can calculate results and put them in the cache (which is
64 allocated if necessary), and then advance to stage Whatever. */
65 
66 #include "simbody/internal/common.h"
67 #include "simbody/internal/Motion.h"
68 
69 #include <cassert>
70 #include <iostream>
71 using std::cout; using std::endl;
72 
73 using namespace SimTK;
74 
75 class SimbodyMatterSubsystemRep;
76 class RigidBodyNode;
77 template <int dof, bool noR_FM, bool noX_MB, bool noR_PF>
78     class RigidBodyNodeSpec;
79 
80 // defined below
81 
82 class SBTopologyCache;
83 class SBModelCache;
84 class SBInstanceCache;
85 class SBTimeCache;
86 class SBTreePositionCache;
87 class SBConstrainedPositionCache;
88 class SBCompositeBodyInertiaCache;
89 class SBArticulatedBodyInertiaCache;
90 class SBTreeVelocityCache;
91 class SBConstrainedVelocityCache;
92 class SBDynamicsCache;
93 class SBTreeAccelerationCache;
94 class SBConstrainedAccelerationCache;
95 
96 class SBModelVars;
97 class SBInstanceVars;
98 class SBTimeVars;
99 class SBPositionVars;
100 class SBVelocityVars;
101 class SBDynamicsVars;
102 class SBAccelerationVars;
103 
104 
105 
106 // =============================================================================
107 //                               TOPOLOGY CACHE
108 // =============================================================================
109 // An object of this type is stored in the SimbodyMatterSubsystem after extended
110 // construction is complete, then copied into a slot in the State upon
111 // realizeTopology(). It should contain enough information to size the Model
112 // stage, and State resource index numbers for the Model-stage state variables
113 // and Model-stage cache entry. This topology cache entry can also contain
114 // whatever arbitrary data you would like to have in a State to verify that it
115 // is a match for the SimbodyMatterSubsystem.
116 //
117 // Note that this does not include all possible topological information in
118 // a SimbodyMatterSubsystem -- any subobjects are free to hold their own
119 // as long as they don't change it after realizeTopology().
120 class SBTopologyCache {
121 public:
SBTopologyCache()122     SBTopologyCache() {clear();}
123 
clear()124     void clear() {
125         nBodies = nParticles = nConstraints = nAncestorConstrainedBodies =
126             nDOFs = maxNQs = sumSqDOFs = -1;
127         modelingVarsIndex.invalidate();
128         modelingCacheIndex.invalidate();
129         topoInstanceVarsIndex.invalidate();
130         valid = false;
131     }
132 
133     // These are topological objects.
134     int nBodies;
135     int nParticles;
136     int nConstraints;
137 
138     // This is the total number of Constrained Bodies appearing in all
139     // Constraints where the Ancestor body is not Ground, excluding the
140     // Ancestor bodies themselves even if they are also Constrained Bodies
141     // (which is common). This is used for sizing pool entries in various
142     // caches to hold precalculated Ancestor-frame data about these bodies.
143     int nAncestorConstrainedBodies;
144 
145     // TODO: these should be moved to Model stage.
146     int nDOFs;
147     int maxNQs;
148     int sumSqDOFs;
149 
150     DiscreteVariableIndex modelingVarsIndex;
151     CacheEntryIndex       modelingCacheIndex,instanceCacheIndex, timeCacheIndex,
152                           treePositionCacheIndex, constrainedPositionCacheIndex,
153                           compositeBodyInertiaCacheIndex,
154                           articulatedBodyInertiaCacheIndex,
155                           treeVelocityCacheIndex, constrainedVelocityCacheIndex,
156                           articulatedBodyVelocityCacheIndex,
157                           dynamicsCacheIndex,
158                           treeAccelerationCacheIndex,
159                           constrainedAccelerationCacheIndex;
160 
161 
162     // These are instance variables that exist regardless of modeling
163     // settings; they are instance variables corresponding to topological
164     // elements of the matter subsystem (e.g. mobilized bodies and constraints).
165     DiscreteVariableIndex topoInstanceVarsIndex;
166 
167     bool valid;
168 };
169 //.............................. TOPOLOGY CACHE ................................
170 
171 
172 // =============================================================================
173 //                                MODEL CACHE
174 // =============================================================================
175 // This cache entry contains counts of various things resulting from the
176 // settings of Model-stage state variables. It also contains the resource index
177 // numbers for all state variable and state cache resources allocated during
178 // realizeModel().
179 //
180 // Model stage is when the mobilizers settle on the meaning of the q's and u's
181 // they will employ, so here is where we count up the total number of q's and
182 // u's and assign particular slots in those arrays to each mobilizer. We also
183 // determine the sizes of related "pools", including the number of q's which
184 // are angles (for sincos calculations), and the number of quaternions in use
185 // (for normalization calculations), and partition the entries in those
186 // pools among the mobilizers.
187 //
188 // Important things we still don't know at this stage:
189 //  - what constraints are enabled
190 //  - how motion will be driven for each coordinate
191 
192 
193 // -----------------------------------------------------------------------------
194 //                      PER MOBILIZED BODY MODEL INFO
195 class SBModelPerMobodInfo {
196 public:
SBModelPerMobodInfo()197     SBModelPerMobodInfo()
198     :   nQInUse(-1), nUInUse(-1), hasQuaternionInUse(false),
199         nQPoolInUse(-1) {}
200 
201     int     nQInUse, nUInUse;
202     QIndex  firstQIndex; // Count from 0 for this SimbodyMatterSubsystem
203     UIndex  firstUIndex;
204 
205     // In case there is a quaternion in use by this Mobilizer: The index
206     // here can be used to find precalculated data associated with this
207     // quaternion, such as its current length.
208     bool                hasQuaternionInUse;
209     // 0..nQInUse-1: which local coordinate starts the quaternion if any?
210     MobilizerQIndex     startOfQuaternion;
211     // assigned slot # for this MB's quat, -1 if none
212     QuaternionPoolIndex quaternionPoolIndex;
213 
214     // Each mobilizer can request some position-cache storage space for
215     // precalculations involving its generalized coordinates q.
216     // Here we keep track of our chunk.
217     int nQPoolInUse; // reserved space in sizeof(Real) units
218     MobodQPoolIndex startInQPool; // offset into pool
219 };
220 
221 
222 // -----------------------------------------------------------------------------
223 //                                MODEL CACHE
224 class SBModelCache {
225 public:
SBModelCache()226     SBModelCache() {clear();}
227 
228     // Restore this cache entry to its just-constructed condition.
clear()229     void clear() {
230         totalNQInUse=totalNUInUse=totalNQuaternionsInUse= -1;
231         totalNQPoolInUse= -1;
232 
233         mobodModelInfo.clear();
234     }
235 
236     // Allocate the entries in this ModelCache based on information provided in
237     // the TopologyCache.
allocate(const SBTopologyCache & tc)238     void allocate(const SBTopologyCache& tc) {
239         mobodModelInfo.resize(tc.nBodies);
240     }
241 
242     // Use these accessors so that you get type checking on the index types.
getNumMobilizedBodies()243     int getNumMobilizedBodies() const {return (int)mobodModelInfo.size();}
updMobodModelInfo(MobilizedBodyIndex mbx)244     SBModelPerMobodInfo& updMobodModelInfo(MobilizedBodyIndex mbx)
245     {   return mobodModelInfo[mbx]; }
getMobodModelInfo(MobilizedBodyIndex mbx)246     const SBModelPerMobodInfo& getMobodModelInfo(MobilizedBodyIndex mbx) const
247     {   return mobodModelInfo[mbx]; }
248 
249 
250     // These are sums over the per-MobilizedBody counts above.
251     int totalNQInUse, totalNUInUse, totalNQuaternionsInUse;
252     int totalNQPoolInUse;
253 
254         // STATE ALLOCATION FOR THIS SUBSYSTEM
255 
256     // Note that a MatterSubsystem is only one of potentially many users of a
257     // System's State, so only a subset of State variables and State Cache
258     // entries belong to it. Here we record the indices we were given when
259     // we asked the State for some resources. All indices are private to this
260     // Subsystem -- they'll start from zero regardless of whether there are
261     // other State resource consumers.
262 
263     QIndex qIndex;  // NOTE: local, currently always zero
264     UIndex uIndex;
265     DiscreteVariableIndex timeVarsIndex, qVarsIndex, uVarsIndex,
266                           dynamicsVarsIndex, accelerationVarsIndex;
267 
268 private:
269     // MobilizedBody 0 is Ground.
270     Array_<SBModelPerMobodInfo,MobilizedBodyIndex> mobodModelInfo;
271 };
272 
273 inline std::ostream& operator<<(std::ostream& o, const SBModelCache& c) {
274     o << "SBModelCache:\n";
275     o << "  " << c.getNumMobilizedBodies() << " Mobilized Bodies:\n";
276     for (MobilizedBodyIndex mbx(0); mbx < c.getNumMobilizedBodies(); ++mbx) {
277         const SBModelPerMobodInfo& mInfo = c.getMobodModelInfo(mbx);
278         o << "  " << mbx << ": nq,nu="   << mInfo.nQInUse << "," << mInfo.nUInUse
279                          <<  " qix,uix=" << mInfo.firstQIndex << "," << mInfo.firstUIndex << endl;
280         if (mInfo.hasQuaternionInUse)
281             o <<  "    firstQuat,quatPoolIx=" << mInfo.startOfQuaternion << "," << mInfo.quaternionPoolIndex << endl;
282         else o << "    no quaternion in use\n";
283         if (mInfo.nQPoolInUse)
284              o << "    nQPool,qPoolIx=" << mInfo.nQPoolInUse << "," << mInfo.startInQPool << endl;
285         else o << "    no angles in use\n";
286     }
287     return o;
288 }
289 //............................... MODEL CACHE ..................................
290 
291 
292 
293 // =============================================================================
294 //                               INSTANCE CACHE
295 // =============================================================================
296 // This is SimbodyMatterSubsystem information calculated during
297 // realizeInstance(), possibly based on the settings of Instance-stage state
298 // variables. At this point we will have determined the following information:
299 //  - final mass properties for all bodies (can calculate total mass)
300 //  - final locations for all mobilizer frames
301 //  - which Constraints are enabled
302 //  - how many and what types of constraint equations are to be included
303 //  - how motion is to be calculated for each mobilizer
304 //
305 // We allocate entries in the constraint error and multiplier pools among the
306 // Constraints, and allocate entries in the prescribed motion and prescribed
307 // force pools among mobilizers whose motion is prescribed.
308 //
309 // At this point we can classify all the mobilizers based on the kind of Motion
310 // they will undergo. We determine the scope of every Constraint, and classify
311 // them based on the kinds of mobilizers they affect.
312 
313 
314 // -----------------------------------------------------------------------------
315 //                      PER MOBILIZED BODY INSTANCE INFO
316 // This is information calculated once we have seen all the Instance-stage
317 // State variable values that can affect bodies, mobilizers, and motions.
318 // Notes:
319 //   - all mobilities of a mobilizer must be treated identically
320 //   - if any motion level is fast, then the whole mobilizer is fast
321 //   - if a mobilizer is fast, so are all its outboard mobilizers
322 class SBInstancePerMobodInfo {
323 public:
SBInstancePerMobodInfo()324     SBInstancePerMobodInfo() {clear();}
325 
clear()326     void clear() {
327         qMethod=uMethod=udotMethod=Motion::Free;
328         firstPresQ.invalidate(); firstPresU.invalidate();
329         firstPresUDot.invalidate(); firstPresForce.invalidate();
330     }
331 
332     Motion::Method      qMethod;        // how are positions calculated?
333     Motion::Method      uMethod;        // how are velocities calculated?
334     Motion::Method      udotMethod;     // how are accelerations calculated?
335 
336     PresQPoolIndex      firstPresQ;     // if qMethod==Prescribed
337     PresUPoolIndex      firstPresU;     // if uMethod==Prescribed
338     PresUDotPoolIndex   firstPresUDot;  // if udotMethod==Prescribed
339     PresForcePoolIndex  firstPresForce; // if udotMethod!=Free
340 };
341 
342 
343 // -----------------------------------------------------------------------------
344 //                       PER CONSTRAINT INSTANCE INFO
345 // Store some Instance-stage information about each Constraint. Most
346 // important, we don't know how many constraint equations (if any) the
347 // Constraint will generate until Instance stage. In particular, a disabled
348 // Constraint won't generate any equations (it will have an Info entry
349 // here, however). Also, although we know the Constrained Mobilizers at
350 // Topology stage, we don't know the specific number or types of internal
351 // coordinates involved until Instance stage.
352 
353 // Helper class for per-constrained mobilizer information.
354 class SBInstancePerConstrainedMobilizerInfo {
355 public:
SBInstancePerConstrainedMobilizerInfo()356     SBInstancePerConstrainedMobilizerInfo()
357     :   nQInUse(0), nUInUse(0) { } // assume disabled
358     // The correspondence between Constrained Mobilizers and Mobilized
359     // Bodies is Topological information you can pull from the
360     // TopologyCache. See the MobilizedBody for counts of its q's and u's,
361     // which define the allocated number of slots for the
362     // ConstrainedMobilizer as well.
363     int nQInUse, nUInUse; // same as corr. MobilizedBody unless disabled
364     ConstrainedQIndex  firstConstrainedQIndex; // these count from 0 for
365     ConstrainedUIndex  firstConstrainedUIndex; //   each Constraint
366 };
367 
368 
369 class SBInstancePerConstraintInfo {
370 public:
SBInstancePerConstraintInfo()371     SBInstancePerConstraintInfo() { }
clear()372     void clear() {
373         constrainedMobilizerInstanceInfo.clear();
374         constrainedQ.clear(); constrainedU.clear();
375         participatingQ.clear(); participatingU.clear();
376     }
377 
allocateConstrainedMobilizerInstanceInfo(int nConstrainedMobilizers)378     void allocateConstrainedMobilizerInstanceInfo(int nConstrainedMobilizers) {
379         assert(nConstrainedMobilizers >= 0);
380         constrainedMobilizerInstanceInfo.resize(nConstrainedMobilizers);
381         constrainedQ.clear();   // build by appending
382         constrainedU.clear();
383     }
384 
getNumConstrainedMobilizers()385     int getNumConstrainedMobilizers() const
386     {   return (int)constrainedMobilizerInstanceInfo.size(); }
387 
388     const SBInstancePerConstrainedMobilizerInfo&
getConstrainedMobilizerInstanceInfo(ConstrainedMobilizerIndex M)389     getConstrainedMobilizerInstanceInfo(ConstrainedMobilizerIndex M) const
390     {   return constrainedMobilizerInstanceInfo[M]; }
391 
392     SBInstancePerConstrainedMobilizerInfo&
updConstrainedMobilizerInstanceInfo(ConstrainedMobilizerIndex M)393     updConstrainedMobilizerInstanceInfo(ConstrainedMobilizerIndex M)
394     {   return constrainedMobilizerInstanceInfo[M]; }
395 
getNumConstrainedQ()396     int getNumConstrainedQ() const {return (int)constrainedQ.size();}
getNumConstrainedU()397     int getNumConstrainedU() const {return (int)constrainedU.size();}
addConstrainedQ(QIndex qx)398     ConstrainedQIndex addConstrainedQ(QIndex qx) {
399         constrainedQ.push_back(qx);
400         return ConstrainedQIndex(constrainedQ.size()-1);
401     }
addConstrainedU(UIndex ux)402     ConstrainedUIndex addConstrainedU(UIndex ux) {
403         constrainedU.push_back(ux);
404         return ConstrainedUIndex(constrainedU.size()-1);
405     }
getQIndexFromConstrainedQ(ConstrainedQIndex i)406     QIndex getQIndexFromConstrainedQ(ConstrainedQIndex i) const
407     {   return constrainedQ[i]; }
getUIndexFromConstrainedU(ConstrainedUIndex i)408     UIndex getUIndexFromConstrainedU(ConstrainedUIndex i) const
409     {   return constrainedU[i]; }
410 
getNumParticipatingQ()411     int getNumParticipatingQ() const {return (int)participatingQ.size();}
getNumParticipatingU()412     int getNumParticipatingU() const {return (int)participatingU.size();}
addParticipatingQ(QIndex qx)413     ParticipatingQIndex addParticipatingQ(QIndex qx) {
414         participatingQ.push_back(qx);
415         return ParticipatingQIndex(participatingQ.size()-1);
416     }
addParticipatingU(UIndex ux)417     ParticipatingUIndex addParticipatingU(UIndex ux) {
418         participatingU.push_back(ux);
419         return ParticipatingUIndex(participatingU.size()-1);
420     }
getQIndexFromParticipatingQ(ParticipatingQIndex i)421     QIndex getQIndexFromParticipatingQ(ParticipatingQIndex i) const
422     {   return participatingQ[i]; }
getUIndexFromParticipatingU(ParticipatingUIndex i)423     UIndex getUIndexFromParticipatingU(ParticipatingUIndex i) const
424     {   return participatingU[i]; }
425 
426     Segment holoErrSegment;    // (offset,mHolo)    for each Constraint, within subsystem qErr
427     Segment nonholoErrSegment; // (offset,mNonholo) same, but for uErr slots (after holo derivs)
428     Segment accOnlyErrSegment; // (offset,mAccOnly) same, but for udotErr slots (after holo/nonholo derivs)
429 
430     Segment consBodySegment;
431     Segment consMobilizerSegment; // mobilizers, not *mobilities*
432     Segment consQSegment;
433     Segment consUSegment;         // these (u) are *mobilities*
434 public:
435     Array_<SBInstancePerConstrainedMobilizerInfo,
436            ConstrainedMobilizerIndex>   constrainedMobilizerInstanceInfo;
437 
438     // The ConstrainedBodies and ConstrainedMobilizers are set at Topology
439     // stage, but the particular generalized coordinates q and generalized
440     // speeds u which are involved can't be determined until Model stage,
441     // since the associated mobilizers have Model stage options which can
442     // affect the number and meanings of these variables. These are sorted
443     // in order of their associated ConstrainedMobilizer, not necessarily
444     // in order of QIndex or UIndex. Each value appears only once.
445     Array_<QIndex,ConstrainedQIndex> constrainedQ; // -> subsystem QIndex
446     Array_<UIndex,ConstrainedUIndex> constrainedU; // -> subsystem UIndex
447 
448     // Participating mobilities include ALL the mobilities which may be
449     // involved in any of this Constraint's constraint equations, whether
450     // from being directly constrained or indirectly as a result of their
451     // effects on ConstrainedBodies. These are sorted in order of
452     // increasing QIndex and UIndex, and each QIndex or UIndex appears
453     // only once.
454     Array_<QIndex,ParticipatingQIndex> participatingQ; // -> subsystem QIndex
455     Array_<UIndex,ParticipatingUIndex> participatingU; // -> subsystem UIndex
456 };
457 
458 
459 // -----------------------------------------------------------------------------
460 //                               INSTANCE CACHE
461 class SBInstanceCache {
462 public:
463     // Instance variables are:
464     //   body mass props; particle masses
465     //   X_BM, X_PF mobilizer transforms
466     //
467     // Calculations stored here derive from those states:
468     //   total mass
469     //   central inertia of each rigid body
470     //   principal axes and corresponding principal moments of inertia of
471     //       each rigid body
472     //   reference configuration X_PB when q==0 (usually that means M==F),
473     //       for each rigid body
474 
475     Real              totalMass; // sum of all rigid body and particles masses
476     Array_<Inertia,MobilizedBodyIndex>   centralInertias;           // nb
477     Array_<Vec3,MobilizedBodyIndex>      principalMoments;          // nb
478     Array_<Rotation,MobilizedBodyIndex>  principalAxes;             // nb
479     Array_<Transform,MobilizedBodyIndex> referenceConfiguration;    // nb
480 
getNumMobilizedBodies()481     int getNumMobilizedBodies() const {return (int)mobodInstanceInfo.size();}
updMobodInstanceInfo(MobilizedBodyIndex mbx)482     SBInstancePerMobodInfo& updMobodInstanceInfo(MobilizedBodyIndex mbx)
483     {   return mobodInstanceInfo[mbx]; }
getMobodInstanceInfo(MobilizedBodyIndex mbx)484     const SBInstancePerMobodInfo& getMobodInstanceInfo(MobilizedBodyIndex mbx) const
485     {   return mobodInstanceInfo[mbx]; }
486     Array_<SBInstancePerMobodInfo,MobilizedBodyIndex> mobodInstanceInfo;
487 
getNumConstraints()488     int getNumConstraints() const {return (int)constraintInstanceInfo.size();}
updConstraintInstanceInfo(ConstraintIndex cx)489     SBInstancePerConstraintInfo& updConstraintInstanceInfo(ConstraintIndex cx)
490     {   return constraintInstanceInfo[cx]; }
getConstraintInstanceInfo(ConstraintIndex cx)491     const SBInstancePerConstraintInfo& getConstraintInstanceInfo(ConstraintIndex cx) const
492     {   return constraintInstanceInfo[cx]; }
493     Array_<SBInstancePerConstraintInfo,ConstraintIndex> constraintInstanceInfo;
494 
495     // This is a sum over all the mobilizers whose q's are currently prescribed,
496     // adding the number of q's (generalized coordinates) nq currently being
497     // used for each of those. An array of size totalNPresQ is allocated in the
498     // TimeCache to hold the calculated q's (which will be different from the
499     // actual q's until they are applied). Motions will also provide this many
500     // prescribed qdots and qdotdots, but we will map those to u's and udots
501     // before recording them, with nu entries being allocated in each. These
502     // nq- and nu-sized slots are allocated in order of MobilizedBodyIndex.
getTotalNumPresQ()503     int getTotalNumPresQ() const {return (int)presQ.size();}
getTotalNumZeroQ()504     int getTotalNumZeroQ() const {return (int)zeroQ.size();}
getTotalNumFreeQ()505     int getTotalNumFreeQ() const {return (int)freeQ.size();}
506     Array_<QIndex> presQ;
507     Array_<QIndex> zeroQ;
508     Array_<QIndex> freeQ; // must be integrated
509 
510     // This is a sum over all the mobilizers whose u's are current prescribed,
511     // whether because of non-holonomic (velocity) prescribed motion u=u(t,q),
512     // or because the q's are prescribed via holonomic (position) prescribed
513     // motion and the u's are calculated from the qdots. We add the number u's
514     // (generalized speeds) nu currently being used for each holonomic- or
515     // nonholonomic-prescribed mobilizer. An array of this size is allocated
516     // in the PositionCache to hold the calculated u's (which will be
517     // different from the actual u's until they are applied). Nu-sized slots
518     // are allocated in order of MobilizedBodyIndex.
getTotalNumPresU()519     int getTotalNumPresU() const {return (int)presU.size();}
getTotalNumZeroU()520     int getTotalNumZeroU() const {return (int)zeroU.size();}
getTotalNumFreeU()521     int getTotalNumFreeU() const {return (int)freeU.size();}
522     Array_<UIndex> presU;
523     Array_<UIndex> zeroU;
524     Array_<UIndex> freeU; // must be integrated
525 
526     // This is a sum over all the mobilizers whose udots are currently
527     // prescribed, adding the number of udots (mobilities) nu from each
528     // holonomic-, nonholonomic-, or acceleration-prescribed mobilizer. An
529     // array of this size is allocated in the DynamicsCache, and an entry is
530     // needed in the prescribed force array in the AccelerationCache as well.
531     // These nu-sized slots are allocated in order of MobilizedBodyIndex.
getTotalNumPresUDot()532     int getTotalNumPresUDot() const {return (int)presUDot.size();}
getTotalNumZeroUDot()533     int getTotalNumZeroUDot() const {return (int)zeroUDot.size();}
getTotalNumFreeUDot()534     int getTotalNumFreeUDot() const {return (int)freeUDot.size();}
535     Array_<UIndex> presUDot;
536     Array_<UIndex> zeroUDot;
537     Array_<UIndex> freeUDot; // calculated from forces
538 
539     // This includes all the mobilizers whose udots are known for any
540     // reason: Prescribed, Zero, Discrete, or Fast (anything but Free).
541     // These need slots in the array of calculated prescribed motion
542     // forces (taus). This maps those tau entries to the mobility at
543     // which they are generalized forces.
getTotalNumPresForces()544     int getTotalNumPresForces() const {return (int)presForce.size();}
545     Array_<UIndex> presForce;
546 
547     // Quaternion errors go in qErr also, but after all the physical contraint
548     // errors. That is, they start at index
549     // totalNHolonomicConstraintEquationsInUse.
550     int firstQuaternionQErrSlot;
551 
552     // These record where in the full System's State our Subsystem's qErr, uErr,
553     // and udotErr entries begin. That is, this subsystem's segments can be
554     // found at
555     //    qErr   (qErrIndex,    nPositionConstraintEquationsInUse
556     //                                        + nQuaternionsInUse)
557     //    uErr   (uErrIndex,    nVelocityConstraintEquationsInUse)
558     //    udotErr(udotErrIndex, nAccelerationConstraintEquationsInUse)
559     int qErrIndex, uErrIndex, udotErrIndex;
560 
561     // These are the sums over the per-Constraint data above. The number of
562     // position constraint equations (not counting quaternion normalization
563     // constraints) is the same as the number of holonomic constraints mHolo.
564     // The number of velocity constraint equations is mHolo+mNonholo. The
565     // number of acceleration constraint equations, and thus the number of
566     // udotErrs and multipliers, is mHolo+mNonholo+mAccOnly.
567     int totalNHolonomicConstraintEquationsInUse;         // sum(mHolo)    (#position equations = mHolo)
568     int totalNNonholonomicConstraintEquationsInUse;      // sum(mNonholo) (#velocity equations = mHolo+mNonholo)
569     int totalNAccelerationOnlyConstraintEquationsInUse;  // sum(mAccOnly) (#acceleration eqns  = mHolo+mNonholo+mAccOnly)
570 
571     int totalNConstrainedBodiesInUse;
572     int totalNConstrainedMobilizersInUse;
573     int totalNConstrainedQInUse; // q,u from the constrained mobilizers
574     int totalNConstrainedUInUse;
575 public:
allocate(const SBTopologyCache & topo,const SBModelCache & model)576     void allocate(const SBTopologyCache& topo,
577                   const SBModelCache&    model)
578     {
579         totalMass = SimTK::NaN;
580         centralInertias.resize(topo.nBodies);           // I_CB
581         principalMoments.resize(topo.nBodies);          // (Ixx,Iyy,Izz)
582         principalAxes.resize(topo.nBodies);             // [axx ayy azz]
583         referenceConfiguration.resize(topo.nBodies);    // X0_PB
584 
585         mobodInstanceInfo.resize(topo.nBodies);
586 
587         constraintInstanceInfo.resize(topo.nConstraints);
588         firstQuaternionQErrSlot = qErrIndex = uErrIndex = udotErrIndex = -1;
589 
590         totalNHolonomicConstraintEquationsInUse        = 0;
591         totalNNonholonomicConstraintEquationsInUse     = 0;
592         totalNAccelerationOnlyConstraintEquationsInUse = 0;
593 
594         totalNConstrainedBodiesInUse     = 0;
595         totalNConstrainedMobilizersInUse = 0;
596         totalNConstrainedQInUse          = 0;
597         totalNConstrainedUInUse          = 0;
598     }
599 
600 };
601 //.............................. INSTANCE CACHE ................................
602 
603 
604 
605 // =============================================================================
606 //                                TIME CACHE
607 // =============================================================================
608 // Here we hold information that is calculated in the SimbodyMatterSubsystem's
609 // realizeTime() method. Currently that consists only of prescribed q's, which
610 // must always be defined as functions of time.
611 
612 class SBTimeCache {
613 public:
614     // This holds values from Motion prescribed position (holonomic) calculations.
615     Array_<Real> presQPool;   // Index with PresQPoolIndex
616 
617 public:
allocate(const SBTopologyCache & topo,const SBModelCache & model,const SBInstanceCache & instance)618     void allocate(const SBTopologyCache& topo,
619                   const SBModelCache&    model,
620                   const SBInstanceCache& instance)
621     {
622         presQPool.resize(instance.getTotalNumPresQ());
623     }
624 };
625 //............................... TIME CACHE ...................................
626 
627 
628 
629 // =============================================================================
630 //                             TREE POSITION CACHE
631 // =============================================================================
632 // Here we hold information that is calculated early in the matter subsystem's
633 // realizePosition() method. This includes
634 //
635 //  - mobilizer matrices X_FM, H_FM, X_PB, H_PB_G
636 //  - basic kinematic information X_GB, Phi_PB_G
637 //  - mass properties expressed in Ground (TODO: these should probably be in
638 //    their own cache since they aren't needed for kinematics)
639 //
640 //  - for constrained bodies, position X_AB of each body in its ancestor A
641 //
642 // This cache entry can be calculated after Stage::Time and is guaranteed to
643 // have been calculated by the end of Stage::Position. The
644 // SimbodyMatterSubsystem's realizePosition() method will mark this done as
645 // soon as possible, so that later calculations (constraint position errors,
646 // prescribed velocities) can access these without a stage violation.
647 
648 class SBTreePositionCache {
649 public:
getX_FM(MobilizedBodyIndex mbx)650     const Transform& getX_FM(MobilizedBodyIndex mbx) const {return bodyJointInParentJointFrame[mbx];}
updX_FM(MobilizedBodyIndex mbx)651     Transform&       updX_FM(MobilizedBodyIndex mbx)       {return bodyJointInParentJointFrame[mbx];}
getX_PB(MobilizedBodyIndex mbx)652     const Transform& getX_PB(MobilizedBodyIndex mbx) const {return bodyConfigInParent[mbx];}
updX_PB(MobilizedBodyIndex mbx)653     Transform&       updX_PB(MobilizedBodyIndex mbx)       {return bodyConfigInParent[mbx];}
getX_GB(MobilizedBodyIndex mbx)654     const Transform& getX_GB(MobilizedBodyIndex mbx) const {return bodyConfigInGround[mbx];}
updX_GB(MobilizedBodyIndex mbx)655     Transform&       updX_GB(MobilizedBodyIndex mbx)       {return bodyConfigInGround[mbx];}
656 
getX_AB(AncestorConstrainedBodyPoolIndex cbpx)657     const Transform& getX_AB(AncestorConstrainedBodyPoolIndex cbpx) const
658     {   return constrainedBodyConfigInAncestor[cbpx]; }
updX_AB(AncestorConstrainedBodyPoolIndex cbpx)659     Transform&       updX_AB(AncestorConstrainedBodyPoolIndex cbpx)
660     {   return constrainedBodyConfigInAncestor[cbpx]; }
661 public:
662     // At model stage, each mobilizer (RBNode) is given a chance to grab
663     // a segment of this cache entry for its own private use. This includes
664     // pre-calculated sincos(q) for mobilizers with angular coordinates,
665     // and all or part of N and NInv for mobilizers for which qdot != u.
666     // Everything must be filled in by the end of realizePosition() but the
667     // mobilizer is free to fill in different parts at different times during
668     // its realizePosition() calculations.
669     Array_<Real, MobodQPoolIndex> mobilizerQCache;
670 
671     // CAUTION: our definition of the H matrix is transposed from those used
672     // by Jain and by Schwieters. Jain would call these H* and Schwieters
673     // would call them H^T, but we call them H.
674     Array_<Vec3> storageForH_FM; // 2 x ndof (H_FM)
675     Array_<Vec3> storageForH;    // 2 x ndof (H_PB_G)
676 
677     Array_<Transform,MobilizedBodyIndex>    bodyJointInParentJointFrame;  // nb (X_FM)
678     Array_<Transform,MobilizedBodyIndex>    bodyConfigInParent;           // nb (X_PB)
679     Array_<Transform,MobilizedBodyIndex>    bodyConfigInGround;           // nb (X_GB)
680     Array_<PhiMatrix,MobilizedBodyIndex>    bodyToParentShift;            // nb (phi)
681 
682     // This contains mass m, p_BBc_G (center of mass location measured from
683     // B origin, expressed in Ground), and G_Bo_G (unit inertia [gyration]
684     // matrix about B's origin, expressed in Ground). Note that this body's
685     // inertia is I_Bo_G = m*G_Bo_G.
686     Array_<SpatialInertia,MobilizedBodyIndex> bodySpatialInertiaInGround; // nb (Mk_G)
687 
688     // This is the body center of mass location measured from the ground
689     // origin and expressed in ground, p_GBc = p_GB + p_BBc_G (above).
690     Array_<Vec3,MobilizedBodyIndex> bodyCOMInGround;                      // nb (p_GBc)
691 
692 
693         // Constrained Body Pool
694 
695     // For Constraints whose Ancestor body A is not Ground G, we assign pool
696     // entries for each of their Constrained Bodies (call the total number
697     // 'nacb') to store the above information but measured and expressed in
698     // the Ancestor frame rather than Ground.
699     Array_<Transform> constrainedBodyConfigInAncestor;   // nacb (X_AB)
700 
701 public:
allocate(const SBTopologyCache & tree,const SBModelCache & model,const SBInstanceCache & instance)702     void allocate(const SBTopologyCache& tree,
703                   const SBModelCache&    model,
704                   const SBInstanceCache& instance)
705     {
706         // Pull out construction-stage information from the tree.
707         const int nBodies = tree.nBodies;
708         const int nDofs   = tree.nDOFs;   // this is the number of u's (nu)
709         const int maxNQs  = tree.maxNQs;  // allocate the max # q's we'll ever need
710         const int nacb    = tree.nAncestorConstrainedBodies;
711 
712         // These contain uninitialized junk. Body-indexed entries get their
713         // ground elements set appropriately now and forever.
714 
715         mobilizerQCache.resize(model.totalNQPoolInUse);
716 
717         storageForH_FM.resize(2*nDofs);
718         storageForH.resize(2*nDofs);
719 
720         bodyJointInParentJointFrame.resize(nBodies);
721         bodyJointInParentJointFrame[GroundIndex].setToZero();
722 
723         bodyConfigInParent.resize(nBodies);
724         bodyConfigInParent[GroundIndex].setToZero();
725 
726         bodyConfigInGround.resize(nBodies);
727         bodyConfigInGround[GroundIndex].setToZero();
728 
729         bodyToParentShift.resize(nBodies);
730         bodyToParentShift[GroundIndex].setToZero();
731 
732         bodySpatialInertiaInGround.resize(nBodies);
733         bodySpatialInertiaInGround[GroundIndex].setMass(Infinity);
734         bodySpatialInertiaInGround[GroundIndex].setMassCenter(Vec3(0));
735         bodySpatialInertiaInGround[GroundIndex].setUnitInertia(UnitInertia(Infinity));
736 
737         bodyCOMInGround.resize(nBodies);
738         bodyCOMInGround[GroundIndex] = Vec3(0);
739 
740         constrainedBodyConfigInAncestor.resize(nacb);
741     }
742 };
743 //.......................... TREE POSITION CACHE ...............................
744 
745 
746 
747 // =============================================================================
748 //                         CONSTRAINED POSITION CACHE
749 // =============================================================================
750 // Here we hold information that is part of the matter subsystem's
751 // realizePosition() calculation but depends on the TreePositionCache having
752 // already been calculated. This includes:
753 //
754 //  - desired values of prescribed u's (since those are functions of at most
755 //    time and position)
756 //  - logically, position constraint errors (qerrs), although in fact that
757 //    array is provided as a built-in by the State
758 //
759 // This cache entry can be calculated after Stage::Time provided that
760 // the SBTreePositionCache entry has already been marked valid. We guarantee
761 // this will have been calculated by Stage::Position.
762 
763 class SBConstrainedPositionCache {
764 public:
765     // qerr cache space is provided directly by the State
766 
767     // This holds values from all the Motion prescribed velocity (nonholonomic)
768     // calculations, and those resulting from diffentiating prescribed positions.
769     Array_<Real> presUPool;   // Index with PresUPoolIndex
770 
771 public:
allocate(const SBTopologyCache & tree,const SBModelCache & model,const SBInstanceCache & instance)772     void allocate(const SBTopologyCache& tree,
773                   const SBModelCache&    model,
774                   const SBInstanceCache& instance)
775     {
776         presUPool.resize(instance.getTotalNumPresU());
777     }
778 };
779 //........................ CONSTRAINED POSITION CACHE ..........................
780 
781 
782 
783 // =============================================================================
784 //                        COMPOSITE BODY INERTIA CACHE
785 // =============================================================================
786 // Composite body inertias R are those that would be felt if all the mobilizers
787 // had prescribed motion (or were welded in their current configurations). These
788 // are convenient for inverse dynamics computations and for scaling of
789 // generalized coordinates and speeds.
790 //
791 // Each spatial inertia here is expressed in the Ground frame but measured about
792 // its body's origin.
793 //
794 // Note that each composite body inertia is a rigid-body spatial inertia, not
795 // the more complicated articulated-body spatial inertia. That means these have
796 // a scalar mass and well-defined mass center, and a very simple structure which
797 // can be exploited for speed. There are at most 10 unique elements in a rigid
798 // body spatial inertia matrix.
799 //
800 // Composite body inertias depend only on positions but are often not needed at
801 // all. So we give them their own cache entry and expect explicit realization
802 // some time after Position stage, if at all.
803 
804 class SBCompositeBodyInertiaCache {
805 public:
806     Array_<SpatialInertia,MobilizedBodyIndex> compositeBodyInertia; // nb (R)
807 
808 public:
allocate(const SBTopologyCache & tree,const SBModelCache & model,const SBInstanceCache & instance)809     void allocate(const SBTopologyCache& tree,
810                   const SBModelCache&    model,
811                   const SBInstanceCache& instance)
812     {
813         // Pull out construction-stage information from the tree.
814         const int nBodies = tree.nBodies;
815 
816         compositeBodyInertia.resize(nBodies); // TODO: ground initialization
817     }
818 };
819 //....................... COMPOSITE BODY INERTIA CACHE .........................
820 
821 
822 
823 // =============================================================================
824 //                       ARTICULATED BODY INERTIA CACHE
825 // =============================================================================
826 /* These articulated body inertias (ABIs) take into account prescribed motion,
827 meaning that they are produced by a combination of articulated and rigid
828 shift operations depending on each mobilizer's current status as "free"
829 or "prescribed". That means that the articulated inertias here are suited
830 only for "mixed" dynamics; you can't use them to calculate M^-1*f unless
831 there is no prescribed motion in the system.
832 
833 Each articulated body inertia here is expressed in the Ground frame but
834 measured about its body's origin.
835 
836 Articulated body inertia matrices, though symmetric and positive
837 definite, do not have the same simple structure as rigid-body (or composite-
838 body) spatial inertias. For example, the apparent mass depends on direction.
839 All 21 elements of this symmetric 6x6 matrix are unique, while there are only
840 10 unique elements in a rigid body spatial inertia.
841 
842 Note that although we use some *rigid* body shift operations here, the
843 results in general are all *articulated* body inertias, because a rigid shift
844 of an articulated body inertia is still an articulated body inertia. Only if
845 all mobilizers are prescribed will these be rigid body spatial inertias. For
846 a discussion of the properties of articulated body inertias, see Section 7.1
847 (pp. 119-123) of Roy Featherstone's excellent 2008 book, Rigid Body Dynamics
848 Algorithms.
849 
850 Intermediate quantities PPlus, D, DI, and G are calculated here which are
851 separately useful when dealing with "free" mobilized bodies. These quantities
852 are not calculated for prescribed mobilizers; they will remain NaN in that
853 case. In particular, this means that the prescribed-mobilizer mass properties
854 do not have to be invertible, so you can have terminal massless bodies as
855 long as their motion is always prescribed.
856 TODO: should D still be calculated? It doesn't require inversion.
857 
858 ABIs depend only on position kinematics (they are time-independent) but are not
859 usually needed until Acceleration stage, and we do not want to compute them
860 earlier because (a) they are expensive, and (b) they require good, invertible
861 mass properties. Some modelers don't bother with good mass properties since they
862 have no intention of doing forward dynamics; they will rightfully complain
863 if they get a singular mass matrix exception in Dynamics stage. So this cache
864 entry should have depends-on stage Instance, with PositionKinematics as an
865 additional prerequisite, and computed-by stage Acceleration. However, it can
866 be realized explicitly any time its stage and prerequisite are valid, such as
867 after Stage::Position. */
868 class SBArticulatedBodyInertiaCache {
869 public:
870     Array_<ArticulatedInertia,MobodIndex> articulatedBodyInertia; // nb (P)
871     Array_<ArticulatedInertia,MobodIndex> pPlus;                  // nb (PPlus)
872 
873     Vector_<Real>       storageForD;    // sum(nu[j]^2)
874     Vector_<Real>       storageForDI;   // sum(nu[j]^2)
875     Array_<Vec3>        storageForG;    // 2 X ndof
876 
877 public:
allocate(const SBTopologyCache & tree,const SBModelCache & model,const SBInstanceCache & instance)878     void allocate(const SBTopologyCache& tree,
879                   const SBModelCache&    model,
880                   const SBInstanceCache& instance)
881     {
882         // Pull out construction-stage information from the tree.
883         const int nBodies = tree.nBodies;
884         const int nDofs   = tree.nDOFs;     // this is the number of u's (nu)
885         const int nSqDofs = tree.sumSqDOFs;   // sum(ndof^2) for each joint
886         const int maxNQs  = tree.maxNQs;  // allocate the max # q's we'll ever need
887 
888         articulatedBodyInertia.resize(nBodies); // TODO: ground initialization
889 
890         pPlus.resize(nBodies); // TODO: ground initialization
891 
892         storageForD.resize(nSqDofs);
893         storageForDI.resize(nSqDofs);
894         storageForG.resize(2*nDofs);
895     }
896 };
897 //....................... ARTICULATED BODY INERTIA CACHE .......................
898 
899 
900 
901 // =============================================================================
902 //                              TREE VELOCITY CACHE
903 // =============================================================================
904 // Here we hold information that is calculated early in the matter subsystem's
905 // realizeVelocity() method. This includes
906 //
907 //  - mobilizer matrices HDot_FM and HDot_PB_G
908 //  - cross mobilizer velocities V_FM, V_PB
909 //  - basic kinematics V_GB giving body velocities in Ground
910 //  - logically, qdot, but that is provided as a built-in cache entry in State
911 //  - for constrained bodies, V_AB giving body velocities in their ancestor A
912 //  - velocity-dependent dynamics remainder terms: coriolis acceleration and
913 //    gyroscopic forces
914 //
915 // This cache entry can be calculated after Stage::Position and is guaranteed to
916 // have been calculated by the end of Stage::Velocity. The matter subsystem's
917 // realizeVelocity() method will mark this done as soon as possible, so that
918 // later calculations (constraint velocity errors) can access these without a
919 // stage violation.
920 
921 class SBTreeVelocityCache {
922 public:
getV_FM(MobodIndex mbx)923     const SpatialVec& getV_FM(MobodIndex mbx) const
924     {   return mobilizerRelativeVelocity[mbx]; }
updV_FM(MobodIndex mbx)925     SpatialVec&       updV_FM(MobodIndex mbx)
926     {   return mobilizerRelativeVelocity[mbx]; }
getV_PB(MobodIndex mbx)927     const SpatialVec& getV_PB(MobodIndex mbx) const
928     {   return bodyVelocityInParent[mbx]; }
updV_PB(MobodIndex mbx)929     SpatialVec&       updV_PB(MobodIndex mbx)
930     {   return bodyVelocityInParent[mbx]; }
getV_GB(MobodIndex mbx)931     const SpatialVec& getV_GB(MobodIndex mbx) const
932     {   return bodyVelocityInGround[mbx]; }
updV_GB(MobodIndex mbx)933     SpatialVec&       updV_GB(MobodIndex mbx)
934     {   return bodyVelocityInGround[mbx]; }
935 
getV_AB(AncestorConstrainedBodyPoolIndex cbpx)936     const SpatialVec& getV_AB(AncestorConstrainedBodyPoolIndex cbpx) const
937     {   return constrainedBodyVelocityInAncestor[cbpx]; }
updV_AB(AncestorConstrainedBodyPoolIndex cbpx)938     SpatialVec&       updV_AB(AncestorConstrainedBodyPoolIndex cbpx)
939     {   return constrainedBodyVelocityInAncestor[cbpx]; }
940 
941 public:
942     // qdot cache space is supplied directly by the State
943 
944     Array_<SpatialVec,MobodIndex> mobilizerRelativeVelocity; // nb (V_FM)
945     Array_<SpatialVec,MobodIndex> bodyVelocityInParent;      // nb (V_PB)
946     Array_<SpatialVec,MobodIndex> bodyVelocityInGround;      // nb (V_GB)
947 
948     // CAUTION: our definition of the H matrix is transposed from those used
949     // by Jain and by Schwieters.
950     Array_<Vec3> storageForHDot_FM;  // 2 x ndof (HDot_FM)
951     Array_<Vec3> storageForHDot;     // 2 x ndof (HDot_PB_G)
952 
953     // nb (VB_PB_G=HDot_PB_G*u)
954     Array_<SpatialVec,MobodIndex> bodyVelocityInParentDerivRemainder;
955 
956     Array_<SpatialVec,MobodIndex> gyroscopicForces;                // nb (b)
957     Array_<SpatialVec,MobodIndex> mobilizerCoriolisAcceleration;   // nb (a)
958     Array_<SpatialVec,MobodIndex> totalCoriolisAcceleration;       // nb (A)
959     Array_<SpatialVec,MobodIndex> totalCentrifugalForces;          // nb (M*A+b)
960 
961 
962         // Ancestor Constrained Body Pool
963 
964     // For Constraints whose Ancestor body A is not Ground G, we assign pool
965     // entries for each of their Constrained Bodies (call the total number
966     // 'nacb') to store the above information but measured and expressed in the
967     // Ancestor frame rather than Ground.
968     Array_<SpatialVec> constrainedBodyVelocityInAncestor; // nacb (V_AB)
969 
970 public:
allocate(const SBTopologyCache & tree,const SBModelCache & model,const SBInstanceCache & instance)971     void allocate(const SBTopologyCache& tree,
972                   const SBModelCache&    model,
973                   const SBInstanceCache& instance)
974     {
975         // Pull out construction-stage information from the tree.
976         const int nBodies = tree.nBodies;
977         const int nDofs   = tree.nDOFs;  // this is the number of u's (nu)
978         const int maxNQs  = tree.maxNQs; // allocate max # q's we'll ever need
979         const int nacb    = tree.nAncestorConstrainedBodies;
980 
981         const SpatialVec SVZero(Vec3(0),Vec3(0));
982 
983         mobilizerRelativeVelocity.resize(nBodies);
984         mobilizerRelativeVelocity[GroundIndex] = SVZero;
985 
986         bodyVelocityInParent.resize(nBodies);
987         bodyVelocityInParent[GroundIndex] = SVZero;
988 
989         bodyVelocityInGround.resize(nBodies);
990         bodyVelocityInGround[GroundIndex] = SVZero;
991 
992         storageForHDot_FM.resize(2*nDofs);
993         storageForHDot.resize(2*nDofs);
994 
995         bodyVelocityInParentDerivRemainder.resize(nBodies);
996         bodyVelocityInParentDerivRemainder[GroundIndex] = SVZero;
997 
998         gyroscopicForces.resize(nBodies);
999         gyroscopicForces[GroundIndex] = SVZero;
1000 
1001         mobilizerCoriolisAcceleration.resize(nBodies);
1002         mobilizerCoriolisAcceleration[GroundIndex] = SVZero;
1003 
1004         totalCoriolisAcceleration.resize(nBodies);
1005         totalCoriolisAcceleration[GroundIndex] = SVZero;
1006 
1007         totalCentrifugalForces.resize(nBodies);
1008         totalCentrifugalForces[GroundIndex] = SVZero;
1009 
1010         constrainedBodyVelocityInAncestor.resize(nacb);
1011     }
1012 };
1013 //............................ TREE VELOCITY CACHE .............................
1014 
1015 
1016 
1017 // =============================================================================
1018 //                         CONSTRAINED VELOCITY CACHE
1019 // =============================================================================
1020 // Here we hold information that is part of the matter subsystem's
1021 // realizeVelocity() calculation but depends on the TreeVelocityCache having
1022 // already been calculated. This includes:
1023 //
1024 //  - (not prescribed udots because we delay those until Dynamics)
1025 //  - logically, velocity constraint errors (uerrs), although in fact that
1026 //    array is provided as a built-in by the State
1027 //
1028 // This cache entry can be calculated after Stage::Position provided that
1029 // the SBTreeVelocityCache entry has already been marked valid. We guarantee
1030 // this will have been calculated by the end of Stage::Velocity.
1031 //
1032 // TODO: currently there is nothing here
1033 class SBConstrainedVelocityCache {
1034 public:
1035     // uerr cache space is provided directly by the State
1036 
1037 public:
allocate(const SBTopologyCache & tree,const SBModelCache & model,const SBInstanceCache & instance)1038     void allocate(const SBTopologyCache& tree,
1039                   const SBModelCache&    model,
1040                   const SBInstanceCache& instance)
1041     {
1042         // nothing yet
1043     }
1044 };
1045 //........................ CONSTRAINED VELOCITY CACHE ..........................
1046 
1047 
1048 // =============================================================================
1049 //                     ARTICULATED BODY VELOCITY CACHE
1050 // =============================================================================
1051 /* This cache entry holds any time-independent precalculations that are
1052 dependent both on velocity kinematics and articulated body inertias (ABIs).
1053 Currently that is just the articulated body centrifugal forces F=P*a+b where P
1054 is the ABI, a is the cross-mobilizer Coriolis acceleration, and b is the
1055 gyroscopic force due to rotational inertia.
1056 
1057 We want to pre-calculate this term for use during Stage::Acceleration because
1058 it does not change as a result of changes to forces in Stage::Dynamics, and it
1059 is common to recalculate accelerations with only forces changing, especially
1060 when dealing with cosntrained systems. But we don't want ot calculate them
1061 prior to Stage::Acceleration because of the dependence on ABIs; see the
1062 comments for SBArticulatedBodyInertiaCache for why. So this cache
1063 entry should have depends-on stage Instance, with VelocityKinematics and ABIs
1064 as an additional prerequisites, and computed-by stage Acceleration. However, it
1065 can be realized any time its stage and prerequisites are valid, such
1066 as after Stage::Velocity plus realizeArticulatedBodyInertias(). */
1067 class SBArticulatedBodyVelocityCache {
1068 public:
1069     Array_<SpatialVec,MobodIndex> articulatedBodyCentrifugalForces; //nb (P*a+b)
1070 
1071 public:
allocate(const SBTopologyCache & tree,const SBModelCache &,const SBInstanceCache &)1072     void allocate(const SBTopologyCache& tree,
1073                   const SBModelCache&,
1074                   const SBInstanceCache&)
1075     {
1076         // Pull out construction-stage information from the tree.
1077         const int nBodies = tree.nBodies;
1078 
1079         articulatedBodyCentrifugalForces.resize(nBodies);
1080         articulatedBodyCentrifugalForces[GroundIndex] =
1081                                                     SpatialVec(Vec3(0),Vec3(0));
1082     }
1083 };
1084 //...................... ARTICULATED BODY VELOCITY CACHE .......................
1085 
1086 
1087 // =============================================================================
1088 //                                DYNAMICS CACHE
1089 // =============================================================================
1090 class SBDynamicsCache {
1091 public:
1092     // This holds the values from all the Motion prescribed acceleration
1093     // calculations, and those which result from diffentiating prescribed
1094     // velocities, or twice-differentiating prescribed positions.
1095     Array_<Real> presUDotPool;    // Index with PresUDotPoolIndex
1096 
1097     Array_<SpatialMat,MobilizedBodyIndex> Y;                          // nb
1098 
1099 public:
allocate(const SBTopologyCache & tree,const SBModelCache &,const SBInstanceCache & instance)1100     void allocate(const SBTopologyCache& tree,
1101                   const SBModelCache&,
1102                   const SBInstanceCache& instance)
1103     {
1104         // Pull out construction-stage information from the tree.
1105         const int nBodies = tree.nBodies;
1106 
1107         presUDotPool.resize(instance.getTotalNumPresUDot());
1108 
1109         Y.resize(nBodies); // TODO: op space compliance kernel (see Jain 2011)
1110         Y[GroundIndex] = SpatialMat(Mat33(0));
1111     }
1112 };
1113 //............................... DYNAMICS CACHE ...............................
1114 
1115 
1116 
1117 // =============================================================================
1118 //                          TREE ACCELERATION CACHE
1119 // =============================================================================
1120 // Here we hold information that is calculated early in the matter subsystem's
1121 // realizeAcceleration() method. This includes
1122 //
1123 //  - basic kinematics A_GB giving body accelerations in Ground
1124 //  - prescribed motion forces tau
1125 //  - logically, udot and qdotdot, but those arrays are provided as built-in
1126 //    cache entries in State
1127 //
1128 //  - mobilizer reaction forces (TODO)
1129 //
1130 // This cache entry can be calculated after Stage::Dynamics and is guaranteed
1131 // to have been calculated by the end of Stage::Acceleration. The matter
1132 // subsystem's realizeAcceleration() method will mark this done as soon as
1133 // possible, so that later calculations (constraint acceleration errors) can
1134 // access these without a stage violation.
1135 
1136 class SBTreeAccelerationCache {
1137 public:
getA_GB(MobilizedBodyIndex mbx)1138     const SpatialVec& getA_GB(MobilizedBodyIndex mbx) const
1139     {   return bodyAccelerationInGround[mbx]; }
updA_GB(MobilizedBodyIndex mbx)1140     SpatialVec&       updA_GB(MobilizedBodyIndex mbx)
1141     {   return bodyAccelerationInGround[mbx]; }
1142 
1143 public:
1144     // udot, qdotdot cache space is provided directly by the State.
1145 
1146     Vector_<SpatialVec> bodyAccelerationInGround; // nb (A_GB)
1147 
1148     // This is where the calculated prescribed motion "taus" go. (That is,
1149     // generalized forces needed to implement prescribed generalized
1150     // accelerations.) Slots here are doled out only for mobilizers that have
1151     // known accelerations; there is one scalar here per mobility in those
1152     // mobilizers. Look in the InstanceCache to see which slots are allocated
1153     // to which mobilizers.
1154     Vector presMotionForces;    // Index with PresForcePoolIndex
1155 
1156     // Temps used in calculating accelerations and prescribed forces.
1157     Vector                                epsilon;  // nu
1158     Array_<SpatialVec,MobilizedBodyIndex> z;        // nb
1159     Array_<SpatialVec,MobilizedBodyIndex> zPlus;    // nb
1160 
1161 public:
allocate(const SBTopologyCache & topo,const SBModelCache &,const SBInstanceCache & instance)1162     void allocate(const SBTopologyCache& topo,
1163                   const SBModelCache&,
1164                   const SBInstanceCache& instance)
1165     {
1166         // Pull out topology-stage information from the tree.
1167         const int nBodies = topo.nBodies;
1168         const int nDofs   = topo.nDOFs;     // this is the number of u's (nu)
1169 
1170         bodyAccelerationInGround.resize(nBodies);
1171         bodyAccelerationInGround[0] = SpatialVec(Vec3(0),Vec3(0));;
1172 
1173         presMotionForces.resize(instance.getTotalNumPresForces());
1174 
1175         epsilon.resize(nDofs);
1176         z.resize(nBodies);
1177         zPlus.resize(nBodies); // TODO: ground initialization
1178     }
1179 };
1180 //.......................... TREE ACCELERATION CACHE ...........................
1181 
1182 
1183 
1184 // =============================================================================
1185 //                        CONSTRAINED ACCELERATION CACHE
1186 // =============================================================================
1187 // Here we hold information that is part of the matter subsystem's
1188 // realizeAcceleration() calculation but depends on the TreeAccelerationCache
1189 // having already been calculated. This includes:
1190 //
1191 //  - logically, acceleration constraint errors (udoterrs), and constraint
1192 //    multipliers, although in fact those arrays are provided as built-ins by
1193 //    the State
1194 //
1195 //  - constraint-generated body and mobility forces
1196 //
1197 // This cache entry can be calculated after Stage::Dynamics provided that
1198 // the SBTreeAccelerationCache entry has already been marked valid. We guarantee
1199 // this will have been calculated by the end of Stage::Acceleration.
1200 
1201 class SBConstrainedAccelerationCache {
1202 public:
1203     // udoterr and multiplier cache space is provided directly by the State.
1204 
1205     // These are ordered by ConstraintIndex, and then by ConstrainedBodyIndex
1206     // within the constraint. Note that they have been re-expressed in G if
1207     // necessary, although they still act at the constrained body origin.
1208     // The same system mobilized body may appear more than once in this list
1209     // if it is affected by multiple Constraints.
1210     Array_<SpatialVec> constrainedBodyForcesInG;    // [ncb]
1211     // Ordered by ConstraintIndex, and then by ConstrainedUIndex within
1212     // the constraint (and those are grouped in order of ConstrainedMobilizer
1213     // for that Constraint). The same system mobility may appear more than once
1214     // in this list if it is involved in multiple constraints.
1215     Array_<Real>       constraintMobilityForces;    // [ncu]
1216 
1217 public:
allocate(const SBTopologyCache &,const SBModelCache &,const SBInstanceCache & instance)1218     void allocate(const SBTopologyCache&,
1219                   const SBModelCache&,
1220                   const SBInstanceCache& instance)
1221     {
1222         const int ncb = instance.totalNConstrainedBodiesInUse;
1223         const int ncu = instance.totalNConstrainedUInUse;
1224 
1225         constrainedBodyForcesInG.resize(ncb);
1226         constraintMobilityForces.resize(ncu);
1227     }
1228 };
1229 //...................... CONSTRAINED ACCELERATION CACHE ........................
1230 
1231 
1232 
1233 
1234 /*
1235  * Generalized state variable collection for a SimbodyMatterSubsystem.
1236  * Variables are divided into Stages, according to when their values
1237  * are needed during a calculation. The Stages are:
1238  *       (Topology: not part of the state. These are the bodies, mobilizers,
1239  *        and topological constraints.)
1240  *     Model:         choice of coordinates, knowns & unknowns, methods, etc.
1241  *     Instance:      setting of physical parameters, e.g. mass
1242  *       (Time: currently there are no time-dependent states or computations)
1243  *     Position:      position and orientation values q (2nd order continuous)
1244  *     Velocity:      generalized speeds u
1245  *     Dynamics:      dynamic quantities & operators available
1246  *     Acceleration:  applied forces and prescribed accelerations
1247  *     Report:        used by study for end-user reporting only; no effect on
1248  *                      results
1249  *
1250  */
1251 
1252 
1253 // =============================================================================
1254 //                                 MODEL VARS
1255 // =============================================================================
1256 // This state variable is allocated during realizeTopology(). Any change made
1257 // to it after that invalidates Stage::Model, requiring realizeModel() to be
1258 // performed.
1259 class SBModelVars {
1260 public:
1261     bool         useEulerAngles;
1262 public:
1263 
1264     // We have to allocate these without looking at any other
1265     // state variable or cache entries. We can only depend on topological
1266     // information.
allocate(const SBTopologyCache & tree)1267     void allocate(const SBTopologyCache& tree) {
1268         useEulerAngles = false;
1269     }
1270 
1271 };
1272 
1273 
1274 
1275 // =============================================================================
1276 //                               INSTANCE VARS
1277 // =============================================================================
1278 // This state variable is allocated during realizeTopology(), because its
1279 // contents refer only to elements that form part of the fixed topology of the
1280 // matter subsystem -- mobilized bodies, particles, and constraints that are
1281 // specified as permanent parts of this matter subsystem.
1282 //
1283 // Any change to this variable invalidates Stage::Instance (not Stage::Model),
1284 // requiring realize(Instance) to be performed.
1285 //
1286 // Note: we may at some point have instance variables whose allocation is
1287 // deferred until realizeModel() but those would be wiped out whenever a change
1288 // to a Model-stage variable is made (most notably useEulerAngles).
1289 class SBInstanceVars {
1290 public:
1291     Array_<MassProperties,MobilizedBodyIndex>   bodyMassProperties;
1292     Array_<Transform,     MobilizedBodyIndex>   outboardMobilizerFrames;
1293     Array_<Transform,     MobilizedBodyIndex>   inboardMobilizerFrames;
1294 
1295     Array_<Motion::Level, MobilizedBodyIndex>   mobilizerLockLevel;
1296     Vector                                      lockedQs;
1297     Vector                                      lockedUs; // also used for udot
1298 
1299     Array_<bool,          MobilizedBodyIndex>   prescribedMotionIsDisabled;
1300 
1301     Vector                                      particleMasses;
1302 
1303     Array_<bool,ConstraintIndex>                constraintIsDisabled;
1304 
1305 public:
1306 
allocate(const SBTopologyCache & topology)1307     void allocate(const SBTopologyCache& topology) {
1308         const int nb = topology.nBodies;
1309         const int np = topology.nParticles;
1310         const int nc = topology.nConstraints;
1311 
1312         // Clear first to make sure all entries are reset to default values.
1313         bodyMassProperties.clear();
1314         bodyMassProperties.resize(nb, MassProperties(1,Vec3(0),Inertia(1)));
1315 
1316         outboardMobilizerFrames.clear();
1317         outboardMobilizerFrames.resize(nb, Transform());
1318 
1319         inboardMobilizerFrames.clear();
1320         inboardMobilizerFrames.resize(nb, Transform());
1321 
1322         mobilizerLockLevel.clear();
1323         mobilizerLockLevel.resize(nb, Motion::NoLevel);
1324 
1325         lockedQs.clear(); // must wait until realize(Model) to size these
1326         lockedUs.clear();
1327 
1328         prescribedMotionIsDisabled.clear();
1329         prescribedMotionIsDisabled.resize(nb, false);
1330 
1331         particleMasses.resize(np);
1332         particleMasses = 1;
1333 
1334         constraintIsDisabled.clear();
1335         constraintIsDisabled.resize(nc, false);
1336     }
1337 
1338 };
1339 
1340 
1341 
1342 // =============================================================================
1343 //                                 TIME VARS
1344 // =============================================================================
1345 class SBTimeVars {
1346 public:
1347     // none
1348 public:
allocate(const SBTopologyCache &)1349     void allocate(const SBTopologyCache&) {
1350     }
1351 };
1352 
1353 
1354 // =============================================================================
1355 //                                POSITION VARS
1356 // =============================================================================
1357 class SBPositionVars {
1358 public:
1359     // none here -- q is supplied directly by the State
1360 public:
allocate(const SBTopologyCache & tree)1361     void allocate(const SBTopologyCache& tree) {
1362     }
1363 };
1364 
1365 
1366 // =============================================================================
1367 //                                VELOCITY VARS
1368 // =============================================================================
1369 class SBVelocityVars  {
1370 public:
1371     // none here -- u is supplied directly by the State
1372 public:
allocate(const SBTopologyCache &)1373     void allocate(const SBTopologyCache&) {
1374     }
1375 };
1376 
1377 
1378 // =============================================================================
1379 //                                DYNAMICS VARS
1380 // =============================================================================
1381 class SBDynamicsVars {
1382 public:
1383     // none here -- z is supplied directly by the State, but not
1384     //              used by the SimbodyMatterSubsystem anyway
1385 public:
allocate(const SBTopologyCache &)1386     void allocate(const SBTopologyCache&) {
1387     }
1388 };
1389 
1390 
1391 
1392 // =============================================================================
1393 //                             ACCELERATION VARS
1394 // =============================================================================
1395 class SBAccelerationVars {
1396 public:
1397     // none here
1398 public:
allocate(const SBTopologyCache & topology)1399     void allocate(const SBTopologyCache& topology) {
1400     }
1401 };
1402 
1403 
1404     /////////////////////
1405     // SB STATE DIGEST //
1406     /////////////////////
1407 
1408 /*
1409  * Objects of this class are constructed for a particular State, and then used
1410  * briefly for a related series of computations. Depending on the stage to which the
1411  * State has been advanced, and the computations to be performed, some or all
1412  * of the pointers here will be set to refer to State and State cache data
1413  * for Simbody, of the types defined above.
1414  *
1415  * The idea is to do all the time consuming work of digging through the State
1416  * just once, then use the results repeatedly for computations which are typically
1417  * performed over all the nodes in the system. The low-level rigid body node computations
1418  * assume already-digested States.
1419  */
1420 class SBStateDigest {
1421 public:
SBStateDigest(const State & s)1422     explicit SBStateDigest(const State& s) : state(s), modifiableState(0), stage(Stage::Empty)
1423     {
1424     }
SBStateDigest(const State & s,const SimbodyMatterSubsystemRep & matter,Stage g)1425     SBStateDigest(const State& s, const SimbodyMatterSubsystemRep& matter, Stage g)
1426       : state(s), modifiableState(0), stage(Stage::Empty)
1427     {
1428         fillThroughStage(matter,g);
1429     }
SBStateDigest(State & s,const SimbodyMatterSubsystemRep & matter,Stage g)1430     SBStateDigest(State& s, const SimbodyMatterSubsystemRep& matter, Stage g)
1431       : state(s), modifiableState(&s), stage(Stage::Empty)
1432     {
1433         fillThroughStage(matter,g);
1434     }
1435 
1436     // Stage g here is the stage we are about to compute. So we expect the referenced
1437     // State to have been realized to at least stage g-1.
1438     void fillThroughStage(const SimbodyMatterSubsystemRep& matter, Stage g);
1439 
1440     // The State is read only, for cache entries you have a choice.
1441 
getState()1442     const State& getState() const {return state;}
updState()1443     State&       updState() {
1444         assert(modifiableState);
1445         return *modifiableState;
1446     }
getStage()1447     Stage        getStage() const {return stage;}
1448 
getModelVars()1449     const SBModelVars& getModelVars() const {
1450         assert(stage >= Stage::Model);
1451         assert(mv);
1452         return *mv;
1453     }
1454 
getInstanceVars()1455     const SBInstanceVars& getInstanceVars() const {
1456         assert(stage >= Stage::Model);
1457         assert(iv);
1458         return *iv;
1459     }
1460 
getTimeVars()1461     const SBTimeVars& getTimeVars() const {
1462         assert(stage >= Stage::Time);
1463         assert(tv);
1464         return *tv;
1465     }
1466 
getQ()1467     const Vector& getQ() const {
1468         assert(stage >= Stage::Model);
1469         assert(q);
1470         return *q;
1471     }
1472 
getPositionVars()1473     const SBPositionVars& getPositionVars() const {
1474         assert(stage >= Stage::Position);
1475         assert(pv);
1476         return *pv;
1477     }
1478 
getU()1479     const Vector& getU() const {
1480         assert(stage >= Stage::Model);
1481         assert(u);
1482         return *u;
1483     }
1484 
getVelocityVars()1485     const SBVelocityVars& getVelocityVars() const {
1486         assert(stage >= Stage::Velocity);
1487         assert(vv);
1488         return *vv;
1489     }
getDynamicsVars()1490     const SBDynamicsVars& getDynamicsVars() const {
1491         assert(stage >= Stage::Dynamics);
1492         assert(dv);
1493         return *dv;
1494     }
getAccelerationVars()1495     const SBAccelerationVars& getAccelerationVars() const {
1496         assert(stage >= Stage::Acceleration);
1497         assert(av);
1498         return *av;
1499     }
1500 
1501     // You can access the cache for update only at the stage being computed.
1502     // You can access the cache read-only for any stage already completed.
1503     // Either way you only need const access to the SBStateDigest object.
1504 
1505     // Model
updModelCache()1506     SBModelCache& updModelCache() const {
1507         assert(stage == Stage::Model);
1508         assert(mc);
1509         return *mc;
1510     }
getModelCache()1511     const SBModelCache& getModelCache() const {
1512         assert(stage > Stage::Model);
1513         assert(mc);
1514         return *mc;
1515     }
1516 
1517     // Instance
updInstanceCache()1518     SBInstanceCache& updInstanceCache() const {
1519         assert(stage == Stage::Instance);
1520         assert(ic);
1521         return *ic;
1522     }
getInstanceCache()1523     const SBInstanceCache& getInstanceCache() const {
1524         assert(stage > Stage::Instance);
1525         assert(ic);
1526         return *ic;
1527     }
1528 
1529     // Time
updTimeCache()1530     SBTimeCache& updTimeCache() const {
1531         assert(stage >= Stage::Instance && stage <= Stage::Time);
1532         assert(tc);
1533         return *tc;
1534     }
getTimeCache()1535     const SBTimeCache& getTimeCache() const {
1536         assert(stage > Stage::Time);
1537         assert(tc);
1538         return *tc;
1539     }
1540 
1541     // Position
updQErr()1542     Vector& updQErr() const {
1543         assert(stage > Stage::Instance);
1544         assert(qErr);
1545         return *qErr;
1546     }
getQErr()1547     const Vector& getQErr() const {
1548         assert(stage > Stage::Position);
1549         assert(qErr);
1550         return *qErr;
1551     }
updTreePositionCache()1552     SBTreePositionCache& updTreePositionCache() const {
1553         assert(stage >= Stage::Instance && stage <= Stage::Position);
1554         assert(tpc);
1555         return *tpc;
1556     }
getTreePositionCache()1557     const SBTreePositionCache& getTreePositionCache() const {
1558         assert(stage > Stage::Instance);
1559         assert(tpc);
1560         return *tpc;
1561     }
updConstrainedPositionCache()1562     SBConstrainedPositionCache& updConstrainedPositionCache() const {
1563         assert(stage >= Stage::Instance && stage <= Stage::Position);
1564         assert(cpc);
1565         return *cpc;
1566     }
getConstrainedPositionCache()1567     const SBConstrainedPositionCache& getConstrainedPositionCache() const {
1568         assert(stage > Stage::Position);
1569         assert(cpc);
1570         return *cpc;
1571     }
1572 
1573     // Velocity
updQDot()1574     Vector& updQDot() const {
1575         assert(stage > Stage::Instance);
1576         assert(qdot);
1577         return *qdot;
1578     }
getQDot()1579     const Vector& getQDot() const {
1580         assert(stage > Stage::Velocity);
1581         assert(qdot);
1582         return *qdot;
1583     }
updUErr()1584     Vector& updUErr() const {
1585         assert(stage > Stage::Instance);
1586         assert(uErr);
1587         return *uErr;
1588     }
getUErr()1589     const Vector& getUErr() const {
1590         assert(stage > Stage::Velocity);
1591         assert(uErr);
1592         return *uErr;
1593     }
updTreeVelocityCache()1594     SBTreeVelocityCache& updTreeVelocityCache() const {
1595         assert(stage >= Stage::Instance && stage <= Stage::Velocity);
1596         assert(tvc);
1597         return *tvc;
1598     }
getTreeVelocityCache()1599     const SBTreeVelocityCache& getTreeVelocityCache() const {
1600         assert(stage > Stage::Instance);
1601         assert(tvc);
1602         return *tvc;
1603     }
updConstrainedVelocityCache()1604     SBConstrainedVelocityCache& updConstrainedVelocityCache() const {
1605         assert(stage >= Stage::Instance && stage <= Stage::Velocity);
1606         assert(cvc);
1607         return *cvc;
1608     }
getConstrainedVelocityCache()1609     const SBConstrainedVelocityCache& getConstrainedVelocityCache() const {
1610         assert(stage > Stage::Velocity);
1611         assert(cvc);
1612         return *cvc;
1613     }
1614 
1615     // Dynamics
updDynamicsCache()1616     SBDynamicsCache& updDynamicsCache() const {
1617         assert(stage >= Stage::Instance && stage <= Stage::Dynamics);
1618         assert(dc);
1619         return *dc;
1620     }
getDynamicsCache()1621     const SBDynamicsCache& getDynamicsCache() const {
1622         assert(stage > Stage::Dynamics);
1623         assert(dc);
1624         return *dc;
1625     }
updUDot()1626     Vector& updUDot() const {
1627         assert(stage >= Stage::Dynamics);
1628         assert(udot);
1629         return *udot;
1630     }
getUDot()1631     const Vector& getUDot() const {
1632         assert(stage > Stage::Dynamics);
1633         assert(udot);
1634         return *udot;
1635     }
updQDotDot()1636     Vector& updQDotDot() const {
1637         assert(stage >= Stage::Dynamics);
1638         assert(qdotdot);
1639         return *qdotdot;
1640     }
getQDotDot()1641     const Vector& getQDotDot() const {
1642         assert(stage > Stage::Dynamics);
1643         assert(qdotdot);
1644         return *qdotdot;
1645     }
1646 
1647     // Accelerations
1648 
updUDotErr()1649     Vector& updUDotErr() const {
1650         assert(stage == Stage::Acceleration);
1651         assert(udotErr);
1652         return *udotErr;
1653     }
getUDotErr()1654     const Vector& getUDotErr() const {
1655         assert(stage > Stage::Acceleration);
1656         assert(udotErr);
1657         return *udotErr;
1658     }
updTreeAccelerationCache()1659     SBTreeAccelerationCache& updTreeAccelerationCache() const {
1660         assert(stage >= Stage::Instance && stage <= Stage::Acceleration);
1661         assert(tac);
1662         return *tac;
1663     }
getTreeAccelerationCache()1664     const SBTreeAccelerationCache& getTreeAccelerationCache() const {
1665         assert(stage > Stage::Acceleration);
1666         assert(tac);
1667         return *tac;
1668     }
updConstrainedAccelerationCache()1669     SBConstrainedAccelerationCache& updConstrainedAccelerationCache() const {
1670         assert(stage >= Stage::Instance && stage <= Stage::Acceleration);
1671         assert(cac);
1672         return *cac;
1673     }
getConstrainedAccelerationCache()1674     const SBConstrainedAccelerationCache& getConstrainedAccelerationCache() const {
1675         assert(stage > Stage::Acceleration);
1676         assert(cac);
1677         return *cac;
1678     }
1679 
clear()1680     void clear() {
1681         // state
1682         mv=0; iv=0; tv=0;
1683         q=0; pv=0;
1684         u=0; vv=0;
1685         dv=0;
1686         av=0;
1687 
1688         // cache
1689         mc=0; ic=0; tc=0;
1690         qErr=0; tpc=0; cpc=0;
1691         qdot=uErr=0; tvc=0; cvc=0;
1692         dc=0;
1693         udot=qdotdot=udotErr=0; tac=0; cac=0;
1694     }
1695 
1696 private:
1697     const State&                    state;
1698     State*                          modifiableState;
1699     Stage                           stage; // the stage to be computed
1700 
1701     const SBModelVars*              mv;
1702     const SBInstanceVars*           iv;
1703     const SBTimeVars*               tv;
1704 
1705     const Vector*                   q;
1706     const SBPositionVars*           pv;
1707 
1708     const Vector*                   u;
1709     const SBVelocityVars*           vv;
1710     const SBDynamicsVars*           dv;
1711     const SBAccelerationVars*       av;
1712 
1713     SBModelCache*                   mc;
1714     SBInstanceCache*                ic;
1715     SBTimeCache*                    tc;
1716 
1717     Vector*                         qErr;
1718     SBTreePositionCache*            tpc;
1719     SBConstrainedPositionCache*     cpc;
1720 
1721     Vector*                         qdot;
1722     Vector*                         uErr;
1723     SBTreeVelocityCache*            tvc;
1724     SBConstrainedVelocityCache*     cvc;
1725 
1726     SBDynamicsCache*                dc;
1727 
1728     Vector*                         udot;
1729     Vector*                         qdotdot;
1730     Vector*                         udotErr;
1731     SBTreeAccelerationCache*        tac;
1732     SBConstrainedAccelerationCache* cac;
1733 };
1734 
1735 #endif // SimTK_SIMBODY_TREE_STATE_H_
1736