Simbody  3.4 (development)
SimbodyMatterSubsystem.h
Go to the documentation of this file.
00001 #ifndef SimTK_SIMBODY_MATTER_SUBSYSTEM_H_
00002 #define SimTK_SIMBODY_MATTER_SUBSYSTEM_H_
00003 
00004 /* -------------------------------------------------------------------------- *
00005  *                               Simbody(tm)                                  *
00006  * -------------------------------------------------------------------------- *
00007  * This is part of the SimTK biosimulation toolkit originating from           *
00008  * Simbios, the NIH National Center for Physics-Based Simulation of           *
00009  * Biological Structures at Stanford, funded under the NIH Roadmap for        *
00010  * Medical Research, grant U54 GM072970. See https://simtk.org/home/simbody.  *
00011  *                                                                            *
00012  * Portions copyright (c) 2006-12 Stanford University and the Authors.        *
00013  * Authors: Michael Sherman                                                   *
00014  * Contributors: Paul Mitiguy                                                 *
00015  *                                                                            *
00016  * Licensed under the Apache License, Version 2.0 (the "License"); you may    *
00017  * not use this file except in compliance with the License. You may obtain a  *
00018  * copy of the License at http://www.apache.org/licenses/LICENSE-2.0.         *
00019  *                                                                            *
00020  * Unless required by applicable law or agreed to in writing, software        *
00021  * distributed under the License is distributed on an "AS IS" BASIS,          *
00022  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.   *
00023  * See the License for the specific language governing permissions and        *
00024  * limitations under the License.                                             *
00025  * -------------------------------------------------------------------------- */
00026 
00027 #include "SimTKcommon.h"
00028 #include "simbody/internal/common.h"
00029 #include "simbody/internal/MobilizedBody.h"
00030 
00031 #include <cassert>
00032 #include <vector>
00033 #include <iostream>
00034 
00035 class SimbodyMatterSubsystemRep;
00036 
00037 namespace SimTK {
00038 
00039 class MobilizedBody;
00040 class MultibodySystem;
00041 class Constraint;
00042 
00130 class SimTK_SIMBODY_EXPORT SimbodyMatterSubsystem : public Subsystem {
00131 public:
00132 
00133 //==============================================================================
00149 explicit SimbodyMatterSubsystem(MultibodySystem&);
00153 SimbodyMatterSubsystem();
00158 ~SimbodyMatterSubsystem() {} // invokes ~Subsystem()
00159 
00164 const MobilizedBody& getMobilizedBody(MobilizedBodyIndex) const;
00165 
00170 MobilizedBody& updMobilizedBody(MobilizedBodyIndex);
00171 
00174 const MobilizedBody::Ground& getGround() const;
00178 MobilizedBody::Ground& updGround();
00185 MobilizedBody::Ground& Ground() {return updGround();}
00186 
00187 
00191 const Constraint& getConstraint(ConstraintIndex) const;
00192 
00196 Constraint& updConstraint(ConstraintIndex);
00197 
00201 void setShowDefaultGeometry(bool show);
00204 bool getShowDefaultGeometry() const;
00205 
00216 int getNumBodies() const;
00217 
00221 int getNumConstraints() const;
00222 
00225 int getNumMobilities() const;
00226 
00229 int getTotalQAlloc() const;
00230 
00234 int getTotalMultAlloc() const;
00235 
00236 
00249 MobilizedBodyIndex   adoptMobilizedBody(MobilizedBodyIndex  parent, 
00250                                         MobilizedBody&      child);
00251 
00262 ConstraintIndex   adoptConstraint(Constraint&);
00263 
00265 SimbodyMatterSubsystem(const SimbodyMatterSubsystem& ss) : Subsystem(ss) {}
00267 SimbodyMatterSubsystem& operator=(const SimbodyMatterSubsystem& ss) 
00268 {   Subsystem::operator=(ss); return *this; }
00269 
00270 
00271 //==============================================================================
00286 void setUseEulerAngles(State& state, bool useEulerAngles) const;
00287 
00290 bool getUseEulerAngles  (const State& state) const;
00291 
00296 int  getNumQuaternionsInUse(const State& state) const;
00297 
00302 bool isUsingQuaternion(const State& state, MobilizedBodyIndex mobodIx) const;
00308 QuaternionPoolIndex getQuaternionPoolIndex(const State& state, 
00309                                            MobilizedBodyIndex mobodIx) const;
00310 
00317 void setConstraintIsDisabled(State&          state, 
00318                              ConstraintIndex constraintIx, 
00319                              bool            shouldDisableConstraint) const;
00320 
00324 bool isConstraintDisabled(const State&, ConstraintIndex constraint) const;
00325 
00332 void convertToEulerAngles(const State& inputState, State& outputState) const;
00333 
00340 void convertToQuaternions(const State& inputState, State& outputState) const; 
00341 
00345 //==============================================================================
00359 Real calcSystemMass(const State& s) const;
00360 
00365 Vec3 calcSystemMassCenterLocationInGround(const State& s) const;
00366 
00371 MassProperties calcSystemMassPropertiesInGround(const State& s) const;
00372 
00377 Inertia calcSystemCentralInertiaInGround(const State& s) const;
00378 
00383 Vec3 calcSystemMassCenterVelocityInGround(const State& s) const;
00384 
00389 Vec3 calcSystemMassCenterAccelerationInGround(const State& s) const;
00390 
00397 SpatialVec calcSystemMomentumAboutGroundOrigin(const State& s) const;
00398 
00406 SpatialVec calcSystemCentralMomentum(const State& s) const;
00407 
00412 Real calcKineticEnergy(const State& state) const;
00415 //==============================================================================
00528 void multiplyBySystemJacobian( const State&         state,
00529                                const Vector&        u,
00530                                Vector_<SpatialVec>& Ju) const;
00531 
00559 void calcBiasForSystemJacobian(const State&         state,
00560                                Vector_<SpatialVec>& JDotu) const;
00561 
00562 
00566 void calcBiasForSystemJacobian(const State&         state,
00567                                Vector&              JDotu) const;
00568 
00620 void multiplyBySystemJacobianTranspose( const State&                state,
00621                                         const Vector_<SpatialVec>&  F_G,
00622                                         Vector&                     f) const;
00623 
00624 
00657 void calcSystemJacobian(const State&            state,
00658                         Matrix_<SpatialVec>&    J_G) const; // nb X nu
00659 
00664 void calcSystemJacobian(const State&            state,
00665                         Matrix&                 J_G) const; // 6 nb X nu
00666 
00667 
00713 void multiplyByStationJacobian(const State&                      state,
00714                                const Array_<MobilizedBodyIndex>& onBodyB,
00715                                const Array_<Vec3>&               stationPInB,
00716                                const Vector&                     u,
00717                                Vector_<Vec3>&                    JSu) const;
00718 
00721 Vec3 multiplyByStationJacobian(const State&         state,
00722                                MobilizedBodyIndex   onBodyB,
00723                                const Vec3&          stationPInB,
00724                                const Vector&        u) const
00725 {
00726     ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
00727     ArrayViewConst_<Vec3>               stations(&stationPInB, &stationPInB+1);
00728     Vector_<Vec3>                       JSu(1);
00729     multiplyByStationJacobian(state, bodies, stations, u, JSu);
00730     return JSu[0];
00731 }
00732 
00733 
00746 void multiplyByStationJacobianTranspose
00747    (const State&                        state,
00748     const Array_<MobilizedBodyIndex>&   onBodyB,
00749     const Array_<Vec3>&                 stationPInB,
00750     const Vector_<Vec3>&                f_GP,
00751     Vector&                             f) const;
00752 
00754 void multiplyByStationJacobianTranspose
00755    (const State&                        state,
00756     MobilizedBodyIndex                  onBodyB,
00757     const Vec3&                         stationPInB,
00758     const Vec3&                         f_GP,
00759     Vector&                             f) const
00760 {
00761     ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
00762     ArrayViewConst_<Vec3>               stations(&stationPInB, &stationPInB+1);
00763     Vector_<Vec3>                       forces(1, f_GP);
00764     multiplyByStationJacobianTranspose(state, bodies, stations, forces, f);
00765 }
00766 
00807 void calcStationJacobian(const State&                        state,
00808                          const Array_<MobilizedBodyIndex>&   onBodyB,
00809                          const Array_<Vec3>&                 stationPInB,
00810                          Matrix_<Vec3>&                      JS) const;
00811 
00813 void calcStationJacobian(const State&       state,
00814                          MobilizedBodyIndex onBodyB,
00815                          const Vec3&        stationPInB,
00816                          RowVector_<Vec3>&  JS) const
00817 {
00818     ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
00819     ArrayViewConst_<Vec3>               stations(&stationPInB, &stationPInB+1);
00820     calcStationJacobian(state, bodies, stations, JS);
00821 }
00822 
00826 void calcStationJacobian(const State&                        state,
00827                          const Array_<MobilizedBodyIndex>&   onBodyB,
00828                          const Array_<Vec3>&                 stationPInB,
00829                          Matrix&                             JS) const;
00830 
00832 void calcStationJacobian(const State&       state,
00833                          MobilizedBodyIndex onBodyB,
00834                          const Vec3&        stationPInB,
00835                          Matrix&            JS) const
00836 {
00837     ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
00838     ArrayViewConst_<Vec3>               stations(&stationPInB, &stationPInB+1);
00839     calcStationJacobian(state, bodies, stations, JS);
00840 }
00841 
00842 
00879 void calcBiasForStationJacobian(const State&                      state,
00880                                 const Array_<MobilizedBodyIndex>& onBodyB,
00881                                 const Array_<Vec3>&               stationPInB,
00882                                 Vector_<Vec3>&                    JSDotu) const;
00883 
00887 void calcBiasForStationJacobian(const State&                      state,
00888                                 const Array_<MobilizedBodyIndex>& onBodyB,
00889                                 const Array_<Vec3>&               stationPInB,
00890                                 Vector&                           JSDotu) const;
00891 
00894 Vec3 calcBiasForStationJacobian(const State&         state,
00895                                 MobilizedBodyIndex   onBodyB,
00896                                 const Vec3&          stationPInB) const
00897 {
00898     ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
00899     ArrayViewConst_<Vec3>               stations(&stationPInB, &stationPInB+1);
00900     Vector_<Vec3>                       JSDotu(1);
00901     calcBiasForStationJacobian(state, bodies, stations, JSDotu);
00902     return JSDotu[0];
00903 }
00904 
00905 
00962 void multiplyByFrameJacobian
00963    (const State&                        state,
00964     const Array_<MobilizedBodyIndex>&   onBodyB,
00965     const Array_<Vec3>&                 originAoInB,
00966     const Vector&                       u,
00967     Vector_<SpatialVec>&                JFu) const;
00968 
00972 SpatialVec multiplyByFrameJacobian( const State&         state,
00973                                     MobilizedBodyIndex   onBodyB,
00974                                     const Vec3&          originAoInB,
00975                                     const Vector&        u) const
00976 {
00977     ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
00978     ArrayViewConst_<Vec3>               stations(&originAoInB, &originAoInB+1);
00979     Vector_<SpatialVec>                 JFu(1);
00980     multiplyByFrameJacobian(state, bodies, stations, u, JFu);
00981     return JFu[0];
00982 }
00983 
00984 
01027 void multiplyByFrameJacobianTranspose
01028    (const State&                        state,
01029     const Array_<MobilizedBodyIndex>&   onBodyB,
01030     const Array_<Vec3>&                 originAoInB,
01031     const Vector_<SpatialVec>&          F_GAo,
01032     Vector&                             f) const;
01033 
01036 void multiplyByFrameJacobianTranspose(  const State&        state,
01037                                         MobilizedBodyIndex  onBodyB,
01038                                         const Vec3&         originAoInB,
01039                                         const SpatialVec&   F_GAo,
01040                                         Vector&             f) const
01041 {
01042     ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
01043     ArrayViewConst_<Vec3>               stations(&originAoInB, &originAoInB+1);
01044     const Vector_<SpatialVec>           forces(1, F_GAo);
01045     multiplyByFrameJacobianTranspose(state, bodies, stations, forces, f);
01046 }
01047 
01048 
01049 
01094 void calcFrameJacobian(const State&                         state,
01095                        const Array_<MobilizedBodyIndex>&    onBodyB,
01096                        const Array_<Vec3>&                  originAoInB,
01097                        Matrix_<SpatialVec>&                 JF) const;
01098 
01101 void calcFrameJacobian(const State&             state,
01102                        MobilizedBodyIndex       onBodyB,
01103                        const Vec3&              originAoInB,
01104                        RowVector_<SpatialVec>&  JF) const
01105 {
01106     ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
01107     ArrayViewConst_<Vec3>               stations(&originAoInB, &originAoInB+1);
01108     calcFrameJacobian(state, bodies, stations, JF);
01109 }
01110 
01114 void calcFrameJacobian(const State&                         state,
01115                        const Array_<MobilizedBodyIndex>&    onBodyB,
01116                        const Array_<Vec3>&                  originAoInB,
01117                        Matrix&                              JF) const;
01118 
01121 void calcFrameJacobian(const State&             state,
01122                        MobilizedBodyIndex       onBodyB,
01123                        const Vec3&              originAoInB,
01124                        Matrix&                  JF) const 
01125 {
01126     ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
01127     ArrayViewConst_<Vec3>               stations(&originAoInB, &originAoInB+1);
01128     calcFrameJacobian(state, bodies, stations, JF);
01129 }
01130 
01173 void calcBiasForFrameJacobian
01174    (const State&                        state,
01175     const Array_<MobilizedBodyIndex>&   onBodyB,
01176     const Array_<Vec3>&                 originAoInB,
01177     Vector_<SpatialVec>&                JFDotu) const;
01178 
01182 void calcBiasForFrameJacobian(const State&                      state,
01183                               const Array_<MobilizedBodyIndex>& onBodyB,
01184                               const Array_<Vec3>&               originAoInB,
01185                               Vector&                           JFDotu) const;
01186 
01190 SpatialVec calcBiasForFrameJacobian(const State&         state,
01191                                     MobilizedBodyIndex   onBodyB,
01192                                     const Vec3&          originAoInB) const
01193 {
01194     ArrayViewConst_<MobilizedBodyIndex> bodies(&onBodyB, &onBodyB+1);
01195     ArrayViewConst_<Vec3>               stations(&originAoInB, &originAoInB+1);
01196     Vector_<SpatialVec>                 JFDotu(1);
01197     calcBiasForFrameJacobian(state, bodies, stations, JFDotu);
01198     return JFDotu[0];
01199 }
01200 
01203 //==============================================================================
01236 void multiplyByM(const State& state, const Vector& a, Vector& Ma) const;
01237 
01317 void multiplyByMInv(const State& state,
01318     const Vector&               v,
01319     Vector&                     MinvV) const;
01320 
01330 void calcM(const State&, Matrix& M) const;
01331 
01345 void calcMInv(const State&, Matrix& MInv) const;
01346 
01391 void calcProjectedMInv(const State&   s,
01392                        Matrix&        GMInvGt) const;
01393 
01438 void solveForConstraintImpulses(const State&     state,
01439                                 const Vector&    deltaV,
01440                                 Vector&          impulse) const;
01441 
01442 
01466 void multiplyByG(const State&  state,
01467                  const Vector& ulike,
01468                  Vector&       Gulike) const {
01469     Vector bias;
01470     calcBiasForMultiplyByG(state, bias);
01471     multiplyByG(state, ulike, bias, Gulike);
01472 }
01473 
01474 
01478 void multiplyByG(const State&  state,
01479                  const Vector& ulike,
01480                  const Vector& bias,
01481                  Vector&       Gulike) const;
01482 
01508 void calcBiasForMultiplyByG(const State& state,
01509                             Vector&      bias) const;
01510 
01524 void calcG(const State& state, Matrix& G) const;
01525 
01526 
01561 void calcBiasForAccelerationConstraints(const State& state,
01562                                         Vector&      bias) const;
01563 
01564 
01598 void multiplyByGTranspose(const State&  state,
01599                           const Vector& lambda,
01600                           Vector&       f) const;
01601     
01613 void calcGTranspose(const State&, Matrix& Gt) const;
01614 
01615 
01666 void multiplyByPq(const State&  state,
01667                   const Vector& qlike,
01668                   Vector&       PqXqlike) const {
01669     Vector biasp;
01670     calcBiasForMultiplyByPq(state, biasp);
01671     multiplyByPq(state, qlike, biasp, PqXqlike);
01672 }
01673 
01674 
01678 void multiplyByPq(const State&  state,
01679                  const Vector&  qlike,
01680                  const Vector&  biasp,
01681                  Vector&        PqXqlike) const;
01682 
01699 void calcBiasForMultiplyByPq(const State& state,
01700                              Vector&      biasp) const;
01701 
01729 void calcPq(const State& state, Matrix& Pq) const;
01730 
01731 
01764 void multiplyByPqTranspose(const State&  state,
01765                            const Vector& lambdap,
01766                            Vector&       f) const;
01767 
01795 void calcPqTranspose(const State& state, Matrix& Pqt) const;
01796 
01813 void calcP(const State& state, Matrix& P) const;
01814 
01818 void calcPt(const State& state, Matrix& Pt) const;
01819 
01820 
01829 void multiplyByN(const State& s, bool transpose, 
01830                  const Vector& in, Vector& out) const;
01831 
01840 void multiplyByNInv(const State& s, bool transpose, 
01841                     const Vector& in, Vector& out) const;
01842 
01852 void multiplyByNDot(const State& s, bool transpose, 
01853                     const Vector& in, Vector& out) const;
01854 
01858 //==============================================================================
01919 void calcAcceleration
01920    (const State&               state,
01921     const Vector&              appliedMobilityForces,
01922     const Vector_<SpatialVec>& appliedBodyForces,
01923     Vector&                    udot,    // output only; no prescribed motions
01924     Vector_<SpatialVec>&       A_GB) const;
01925 
01949 void calcAccelerationIgnoringConstraints
01950    (const State&                state,
01951     const Vector&               appliedMobilityForces,
01952     const Vector_<SpatialVec>&  appliedBodyForces,
01953     Vector&                     udot,    
01954     Vector_<SpatialVec>&        A_GB) const;
01955 
01956 
01957 
02012 void calcResidualForceIgnoringConstraints
02013    (const State&               state,
02014     const Vector&              appliedMobilityForces,
02015     const Vector_<SpatialVec>& appliedBodyForces,
02016     const Vector&              knownUdot,
02017     Vector&                    residualMobilityForces) const;
02018 
02019 
02082 void calcResidualForce
02083    (const State&               state,
02084     const Vector&              appliedMobilityForces,
02085     const Vector_<SpatialVec>& appliedBodyForces,
02086     const Vector&              knownUdot,
02087     const Vector&              knownLambda,
02088     Vector&                    residualMobilityForces) const;
02089 
02090 
02101 void calcCompositeBodyInertias(const State&    state,
02102     Array_<SpatialInertia,MobilizedBodyIndex>& R) const;
02103 
02104 
02105 
02143 void calcBodyAccelerationFromUDot(const State&         state,
02144                                   const Vector&        knownUDot,
02145                                   Vector_<SpatialVec>& A_GB) const;
02146 
02147 
02170 void calcConstraintForcesFromMultipliers
02171   (const State&         state, 
02172    const Vector&        multipliers,
02173    Vector_<SpatialVec>& bodyForcesInG,
02174    Vector&              mobilityForces) const;
02175 
02258 void calcMobilizerReactionForces
02259    (const State&         state, 
02260     Vector_<SpatialVec>& forcesAtMInG) const;
02261 
02268 const Vector& getMotionMultipliers(const State& state) const;
02269 
02283 Vector calcMotionErrors(const State& state, const Stage& stage) const;
02284 
02290 void findMotionForces
02291    (const State&         state,
02292     Vector&              mobilityForces) const;
02293 
02300 const Vector& getConstraintMultipliers(const State& state) const;
02301 
02306 void findConstraintForces
02307   (const State&         state, 
02308    Vector_<SpatialVec>& bodyForcesInG,
02309    Vector&              mobilityForces) const;
02310 
02326 Real calcMotionPower(const State& state) const;
02327 
02354 Real calcConstraintPower(const State& state) const;
02355 
02361 void calcTreeEquivalentMobilityForces(const State&, 
02362     const Vector_<SpatialVec>& bodyForces,
02363     Vector&                    mobilityForces) const;
02364 
02365 
02370 void calcQDot(const State& s,
02371     const Vector& u,
02372     Vector&       qdot) const;
02373 
02379 void calcQDotDot(const State& s,
02380     const Vector& udot,
02381     Vector&       qdotdot) const;
02382 
02393 void addInStationForce(const State&         state, 
02394                        MobilizedBodyIndex   bodyB, 
02395                        const Vec3&          stationOnB, 
02396                        const Vec3&          forceInG, 
02397                        Vector_<SpatialVec>& bodyForcesInG) const;
02398 
02405 void addInBodyTorque(const State&           state, 
02406                      MobilizedBodyIndex     mobodIx, 
02407                      const Vec3&            torqueInG, 
02408                      Vector_<SpatialVec>&   bodyForcesInG) const;
02409 
02418 void addInMobilityForce(const State&        state,
02419                         MobilizedBodyIndex  mobodIx, 
02420                         MobilizerUIndex     which, 
02421                         Real                f,
02422                         Vector&             mobilityForces) const;
02427 //==============================================================================
02442     // POSITION STAGE realizations //
02443 
02452 void realizeCompositeBodyInertias(const State&) const;
02453 
02463 void realizeArticulatedBodyInertias(const State&) const;
02464 
02465 
02466     // INSTANCE STAGE responses //
02467 
02468 const Array_<QIndex>& getFreeQIndex(const State& state) const;
02469 const Array_<UIndex>& getFreeUIndex(const State& state) const;
02470 const Array_<UIndex>& getFreeUDotIndex(const State& state) const;
02471 const Array_<UIndex>& getKnownUDotIndex(const State& state) const;
02472 void packFreeQ
02473    (const State& s, const Vector& allQ, Vector& packedFreeQ) const;
02474 void unpackFreeQ
02475    (const State& s, const Vector& packedFreeQ, Vector& unpackedFreeQ) const;
02476 void packFreeU
02477    (const State& s, const Vector& allU, Vector& packedFreeU) const;
02478 void unpackFreeU
02479    (const State& s, const Vector& packedFreeU, Vector& unpackedFreeU) const;
02480 
02481 
02482     // POSITION STAGE responses //
02483 
02493 const SpatialInertia& 
02494 getCompositeBodyInertia(const State& state, MobilizedBodyIndex mbx) const;
02495 
02506 const ArticulatedInertia& 
02507 getArticulatedBodyInertia(const State& state, MobilizedBodyIndex mbx) const;
02508 
02509 
02510     // VELOCITY STAGE responses //
02511 
02516 const SpatialVec& 
02517 getGyroscopicForce(const State& state, MobilizedBodyIndex mbx) const;
02518 
02524 const SpatialVec& 
02525 getMobilizerCoriolisAcceleration(const State&       state, 
02526                                  MobilizedBodyIndex mbx) const;
02527 
02536 const SpatialVec& 
02537 getTotalCoriolisAcceleration(const State& state, MobilizedBodyIndex mbx) const;
02538 
02539 
02540     // DYNAMICS STAGE responses //
02541 
02548 const SpatialVec& 
02549 getMobilizerCentrifugalForces(const State& state, MobilizedBodyIndex mbx) const;
02550 
02556 const SpatialVec& 
02557 getTotalCentrifugalForces(const State& state, MobilizedBodyIndex mbx) const;
02562 //==============================================================================
02593 void calcMobilizerReactionForcesUsingFreebodyMethod
02594    (const State&         state, 
02595     Vector_<SpatialVec>& forcesAtMInG) const;
02596 
02600 void invalidateCompositeBodyInertias(const State& state) const;
02601 
02607 void invalidateArticulatedBodyInertias(const State& state) const;
02611 //==============================================================================
02622 
02623 int getNumParticles() const;
02624 
02625 // The generalized coordinates for a particle are always the three measure numbers
02626 // (x,y,z) of the particle's Ground-relative Cartesian location vector. The generalized
02627 // speeds are always the three corresponding measure numbers of the particle's
02628 // Ground-relative Cartesian velocity. The generalized applied forces are
02629 // always the three measure numbers of a Ground-relative force vector.
02630 const Vector_<Vec3>& getAllParticleLocations    (const State&) const;
02631 const Vector_<Vec3>& getAllParticleVelocities   (const State&) const;
02632 
02633 const Vec3& getParticleLocation(const State& s, ParticleIndex p) const {
02634     return getAllParticleLocations(s)[p];
02635 }
02636 const Vec3& getParticleVelocity(const State& s, ParticleIndex p) const {
02637     return getAllParticleVelocities(s)[p];
02638 }
02639 
02640 Vector& updAllParticleMasses(State& s) const;
02641 
02642 void setAllParticleMasses(State& s, const Vector& masses) const {
02643     updAllParticleMasses(s) = masses;
02644 }
02645 
02646 // Note that particle generalized coordinates, speeds, and applied forces
02647 // are defined to be the particle Cartesian locations, velocities, and
02648 // applied force vectors, so can be set directly at Stage::Model or higher.
02649 
02650 // These are the only routines that must be provided by the concrete MatterSubsystem.
02651 Vector_<Vec3>& updAllParticleLocations(State&)     const;
02652 Vector_<Vec3>& updAllParticleVelocities(State&)    const;
02653 
02654 // The following inline routines are provided by the generic MatterSubsystem 
02655 // class for convenience.
02656 
02657 Vec3& updParticleLocation(State& s, ParticleIndex p) const {
02658     return updAllParticleLocations(s)[p];
02659 }
02660 Vec3& updParticleVelocity(State& s, ParticleIndex p) const {
02661     return updAllParticleVelocities(s)[p];
02662 }
02663 
02664 void setParticleLocation(State& s, ParticleIndex p, const Vec3& r) const {
02665     updAllParticleLocations(s)[p] = r;
02666 }
02667 void setParticleVelocity(State& s, ParticleIndex p, const Vec3& v) const {
02668     updAllParticleVelocities(s)[p] = v;
02669 }
02670 
02671 void setAllParticleLocations(State& s, const Vector_<Vec3>& r) const {
02672     updAllParticleLocations(s) = r;
02673 }
02674 void setAllParticleVelocities(State& s, const Vector_<Vec3>& v) const {
02675     updAllParticleVelocities(s) = v;
02676 }
02677 
02678 const Vector& getAllParticleMasses(const State&) const;
02679 
02680 const Vector_<Vec3>& getAllParticleAccelerations(const State&) const;
02681 
02682 const Vec3& getParticleAcceleration(const State& s, ParticleIndex p) const {
02683     return getAllParticleAccelerations(s)[p];
02684 }
02687 //==============================================================================
02696 private:
02699 void calcSpatialKinematicsFromInternal(const State&         state,
02700                                        const Vector&        u,
02701                                        Vector_<SpatialVec>& Ju) const
02702 {   multiplyBySystemJacobian(state,u,Ju); }
02703 
02706 void calcInternalGradientFromSpatial(const State&               state,
02707                                      const Vector_<SpatialVec>& F_G,
02708                                      Vector&                    f) const
02709 {   multiplyBySystemJacobianTranspose(state, F_G, f); }
02710 
02713 void calcMV(const State& state, const Vector& v, Vector& MV) const
02714 {   multiplyByM(state,v,MV); }
02715 
02718 void calcMInverseV(const State& state,
02719     const Vector&               v,
02720     Vector&                     MinvV) const
02721 {   multiplyByMInv(state,v,MinvV); }
02722 
02725 void calcPNInv(const State& state, Matrix& PNInv) const;
02726 
02729 void calcGt(const State&, Matrix& Gt) const;
02730 
02731 
02735 //==============================================================================
02736 //     Bookkeeping methods and internal types -- hide from Doxygen
02738 public:
02739 class Subtree; // used for working with a connected subgraph of the MobilizedBody tree
02740 class SubtreeResults;
02741 
02742 
02743 SimTK_PIMPL_DOWNCAST(SimbodyMatterSubsystem, Subsystem);
02744 const SimbodyMatterSubsystemRep& getRep() const;
02745 SimbodyMatterSubsystemRep&       updRep();
02748 private:
02749 };
02750 
02754 SimTK_SIMBODY_EXPORT std::ostream& 
02755 operator<<(std::ostream&, const SimbodyMatterSubsystem&);
02756 
02757 
02758 } // namespace SimTK
02759 
02760 #endif // SimTK_SIMBODY_MATTER_SUBSYSTEM_H_
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines