Choreonoid  1.5
Classes | Public Member Functions | Public Attributes | List of all members
cnoid::ForwardDynamicsCBM Class Reference

#include <ForwardDynamicsCBM.h>

Inheritance diagram for cnoid::ForwardDynamicsCBM:
cnoid::ForwardDynamics

Public Member Functions

 ForwardDynamicsCBM (DyBody *body)
 
 ~ForwardDynamicsCBM ()
 
void setHighGainModeForAllJoints ()
 
void setHighGainMode (int linkIndex, bool on=true)
 
virtual void initialize ()
 
virtual void calcNextState ()
 
void initializeAccelSolver ()
 
void sumExternalForces ()
 
void solveUnknownAccels ()
 
void solveUnknownAccels (const Vector3 &fext, const Vector3 &tauext)
 
void solveUnknownAccels (DyLink *link, const Vector3 &fext, const Vector3 &tauext, const Vector3 &rootfext, const Vector3 &roottauext)
 
- Public Member Functions inherited from cnoid::ForwardDynamics
 ForwardDynamics (DyBody *body)
 
virtual ~ForwardDynamics ()
 
void setGravityAcceleration (const Vector3 &g)
 
void setEulerMethod ()
 
void setRungeKuttaMethod ()
 
void setTimeStep (double timeStep)
 
void enableSensors (bool on)
 
void setOldAccelSensorCalcMode (bool on)
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
- Public Attributes inherited from cnoid::ForwardDynamics
 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Additional Inherited Members

- Protected Types inherited from cnoid::ForwardDynamics
enum  { EULER_METHOD, RUNGEKUTTA_METHOD }
 
- Static Protected Member Functions inherited from cnoid::ForwardDynamics
static void SE3exp (Position &out_T, const Position &T0, const Vector3 &w, const Vector3 &vo, double dt)
 update position/orientation using spatial velocity More...
 
- Protected Attributes inherited from cnoid::ForwardDynamics
DyBodyPtr body
 
Vector3 g
 
double timeStep
 
bool sensorsEnabled
 
BasicSensorSimulationHelper sensorHelper
 
enum cnoid::ForwardDynamics:: { ... }  integrationMode
 

Detailed Description

The ForwardDynamicsCBM 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.

Constructor & Destructor Documentation

ForwardDynamicsCBM::ForwardDynamicsCBM ( DyBody body)
ForwardDynamicsCBM::~ForwardDynamicsCBM ( )

Member Function Documentation

void ForwardDynamicsCBM::calcNextState ( )
virtual
void ForwardDynamicsCBM::initialize ( void  )
virtual
void ForwardDynamicsCBM::initializeAccelSolver ( )
void ForwardDynamicsCBM::setHighGainMode ( int  linkIndex,
bool  on = true 
)
void ForwardDynamicsCBM::setHighGainModeForAllJoints ( )
void ForwardDynamicsCBM::solveUnknownAccels ( )
void ForwardDynamicsCBM::solveUnknownAccels ( const Vector3 fext,
const Vector3 tauext 
)
void ForwardDynamicsCBM::solveUnknownAccels ( DyLink link,
const Vector3 fext,
const Vector3 tauext,
const Vector3 rootfext,
const Vector3 roottauext 
)
void ForwardDynamicsCBM::sumExternalForces ( )

Member Data Documentation

cnoid::ForwardDynamicsCBM::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

The documentation for this class was generated from the following files: