Choreonoid
1.5
|
#include <ForwardDynamicsABM.h>
Public Member Functions | |
ForwardDynamicsABM (DyBody *body) | |
~ForwardDynamicsABM () | |
virtual void | initialize () |
virtual void | calcNextState () |
![]() | |
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 | |
![]() | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | |
Additional Inherited Members | |
![]() | |
enum | { EULER_METHOD, RUNGEKUTTA_METHOD } |
![]() | |
virtual void | initializeSensors () |
![]() | |
static void | SE3exp (Position &out_T, const Position &T0, const Vector3 &w, const Vector3 &vo, double dt) |
update position/orientation using spatial velocity More... | |
![]() | |
DyBodyPtr | body |
Vector3 | g |
double | timeStep |
bool | sensorsEnabled |
BasicSensorSimulationHelper | sensorHelper |
enum cnoid::ForwardDynamics:: { ... } | integrationMode |
Forward dynamics calculation using Featherstone's Articulated Body Method (ABM)
ForwardDynamicsABM::ForwardDynamicsABM | ( | DyBody * | body | ) |
ForwardDynamicsABM::~ForwardDynamicsABM | ( | ) |
|
virtual |
Implements cnoid::ForwardDynamics.
|
virtual |
Implements cnoid::ForwardDynamics.
cnoid::ForwardDynamicsABM::EIGEN_MAKE_ALIGNED_OPERATOR_NEW |