Choreonoid  1.1
構成 | Public メソッド | すべてのメンバ一覧
クラス cnoid::ForwardDynamicsMM

#include <ForwardDynamicsCBM.h>

cnoid::ForwardDynamicsMMに対する継承グラフ
cnoid::ForwardDynamics

Public メソッド

 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)
 
- Public メソッド inherited from 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)
 

Additional Inherited Members

- Protected 型 inherited from cnoid::ForwardDynamics
enum  { EULER_METHOD, RUNGEKUTTA_METHOD }
 
- Protected メソッド inherited from cnoid::ForwardDynamics
virtual void updateSensorsFinal ()
 
- Static Protected メソッド inherited from 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 [詳細]
 
- Protected 変数 inherited from 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 ( )

関数

void ForwardDynamicsMM::calcNextState ( )
virtual

cnoid::ForwardDynamicsを実装しています。

void ForwardDynamicsMM::initialize ( void  )
virtual

cnoid::ForwardDynamicsを実装しています。

void ForwardDynamicsMM::initializeAccelSolver ( )
void ForwardDynamicsMM::solveUnknownAccels ( const Vector3 fext,
const Vector3 tauext 
)
void ForwardDynamicsMM::solveUnknownAccels ( Link link,
const Vector3 fext,
const Vector3 tauext,
const Vector3 rootfext,
const Vector3 roottauext 
)

このクラスの説明は次のファイルから生成されました: