|
Choreonoid
1.1
|
#include <ForwardDynamicsCBM.h>
公開メンバ関数 | |
| ForwardDynamicsMM (BodyPtr body) | |
| ~ForwardDynamicsMM () | |
| virtual void | initialize () |
| virtual void | calcNextState () |
| void | initializeAccelSolver () |
| void | solveUnknownAccels (const Vector3 &fext, const Vector3 &tauext) |
| void | solveUnknownAccels (Link *link, const Vector3 &fext, const Vector3 &tauext, const Vector3 &rootfext, const Vector3 &roottauext) |
基底クラス cnoid::ForwardDynamics に属する継承公開メンバ関数 | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ForwardDynamics (BodyPtr body) |
| virtual | ~ForwardDynamics () |
| void | setGravityAcceleration (const Vector3 &g) |
| void | setEulerMethod () |
| void | setRungeKuttaMethod () |
| void | setTimeStep (double timeStep) |
| void | enableSensors (bool on) |
その他の継承メンバ | |
基底クラス cnoid::ForwardDynamics に属する継承限定公開型 | |
| enum | { EULER_METHOD, RUNGEKUTTA_METHOD } |
基底クラス cnoid::ForwardDynamics に属する継承限定公開メンバ関数 | |
| virtual void | updateSensorsFinal () |
基底クラス cnoid::ForwardDynamics に属する継承静的限定公開メンバ関数 | |
| static void | SE3exp (Vector3 &out_p, Matrix3 &out_R, const Vector3 &p0, const Matrix3 &R0, const Vector3 &w, const Vector3 &vo, double dt) |
| update position/orientation using spatial velocity [詳解] | |
基底クラス cnoid::ForwardDynamics に属する継承限定公開変数類 | |
| BodyPtr | body |
| Vector3 | g |
| double | timeStep |
| bool | sensorsEnabled |
| enum cnoid::ForwardDynamics:: { ... } | integrationMode |
The ForwardDynamicsMM class calculates the forward dynamics using the motion equation based on the generalized mass matrix. The class is mainly used for a body that has high-gain mode joints. If all the joints of a body are the torque mode, the ForwardDynamicsABM, which uses the articulated body method, is more efficient.
| ForwardDynamicsMM::ForwardDynamicsMM | ( | BodyPtr | body | ) |
| ForwardDynamicsMM::~ForwardDynamicsMM | ( | ) |
|
virtual |
cnoid::ForwardDynamicsを実装しています。
|
virtual |
cnoid::ForwardDynamicsを実装しています。
| void ForwardDynamicsMM::initializeAccelSolver | ( | ) |
| void ForwardDynamicsMM::solveUnknownAccels | ( | Link * | link, |
| const Vector3 & | fext, | ||
| const Vector3 & | tauext, | ||
| const Vector3 & | rootfext, | ||
| const Vector3 & | roottauext | ||
| ) |
1.8.9.1