|
Robotics Library
0.7.0
|
Go to the documentation of this file.
27 #ifndef RL_MDL_DYNAMIC_H
28 #define RL_MDL_DYNAMIC_H
349 #endif // RL_MDL_DYNAMIC_H
::Eigen::Matrix< Real, ::Eigen::Dynamic, ::Eigen::Dynamic > Matrix
Definition: Matrix.h:42
::rl::math::Matrix M
Joint space mass matrix.
Definition: Dynamic.h:330
void forwardDynamics()
Forward dynamics via articulated-body algorithm.
Definition: Dynamic.cpp:210
virtual void update()
Definition: Dynamic.cpp:362
const ::rl::math::Matrix & getOperationalMassMatrixInverse() const
Access calculated operational space mass matrix inverse.
Definition: Dynamic.cpp:253
Dynamic()
Definition: Dynamic.cpp:45
void setWorldGravity(const ::rl::math::Real &x, const ::rl::math::Real &y, const ::rl::math::Real &z)
Definition: Dynamic.cpp:350
const ::rl::math::Vector & getGravity() const
Access calculated gravity vector.
Definition: Dynamic.cpp:235
Definition: Kinematic.h:39
void calculateCentrifugalCoriolis()
Calculate centrifugal and Coriolis vector.
Definition: Dynamic.cpp:60
void calculateOperationalMassMatrixInverse()
Calculate operational space mass matrix inverse.
Definition: Dynamic.cpp:171
::Eigen::Matrix< Real, ::Eigen::Dynamic, 1 > Vector
Definition: Vector.h:42
::rl::math::Matrix J
Jacobian matrix.
Definition: Kinematic.h:262
const ::rl::math::Vector & getCentrifugalCoriolis() const
Access calculated centrifugal and Coriolis vector.
Definition: Dynamic.cpp:229
const ::rl::math::Matrix & getMassMatrix() const
Access calculated joint space mass matrix.
Definition: Dynamic.cpp:247
::rl::math::Vector V
Centrifugal and Coriolis vector.
Definition: Dynamic.h:341
const ::rl::math::Matrix & getMassMatrixInverse() const
Access calculated joint space mass matrix inverse.
Definition: Dynamic.cpp:241
void calculateMassMatrix()
Calculate joint space mass matrix.
Definition: Dynamic.cpp:103
void inverseDynamics()
Inverse dynamics via recursive Newton-Euler algorithm.
Definition: Dynamic.cpp:271
void getWorldGravity(::rl::math::Real &x, ::rl::math::Real &y, ::rl::math::Real &z) const
Definition: Dynamic.cpp:259
::rl::math::Vector G
Gravity vector.
Definition: Dynamic.h:297
Model * clone() const
Definition: Dynamic.cpp:183
void eulerCauchy(const ::rl::math::Real &dt)
Integration via Euler-Cauchy.
Definition: Dynamic.cpp:189
void calculateGravity()
Calculate gravity vector.
Definition: Dynamic.cpp:84
virtual ~Dynamic()
Definition: Dynamic.cpp:55
void rungeKuttaNystrom(const ::rl::math::Real &dt)
Integration via Runge-Kutta-Nyström.
Definition: Dynamic.cpp:294
double Real
Definition: Real.h:42
void calculateMassMatrixInverse()
Calculate joint space mass matrix inverse.
Definition: Dynamic.cpp:137
::rl::math::Matrix invM
Joint space mass matrix inverse.
Definition: Dynamic.h:308
::rl::math::Matrix invMx
Operational space mass matrix inverse.
Definition: Dynamic.h:319
void inverseForce()
Definition: Dynamic.cpp:285
Robotics Library.
Definition: AnalogInput.cpp:30