Robotics Library  0.7.0
Dynamic.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2009, Markus Rickert
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright notice,
11 // this list of conditions and the following disclaimer in the documentation
12 // and/or other materials provided with the distribution.
13 //
14 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
15 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
16 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
17 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
18 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
19 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
20 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
21 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
22 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
23 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
24 // POSSIBILITY OF SUCH DAMAGE.
25 //
26 
27 #ifndef RL_MDL_DYNAMIC_H
28 #define RL_MDL_DYNAMIC_H
29 
30 #include "Kinematic.h"
31 
32 namespace rl
33 {
34  namespace mdl
35  {
36  class Dynamic : public Kinematic
37  {
38  public:
39  Dynamic();
40 
41  virtual ~Dynamic();
42 
53 
65 
74  void calculateGravity();
75 
86 
95  void calculateMassMatrix();
96 
107 
117 
128 
139 
148 
149  Model* clone() const;
150 
171 
182  void forwardDynamics();
183 
193 
203 
215 
224 
237 
238  void getWorldGravity(::rl::math::Real& x, ::rl::math::Real& y, ::rl::math::Real& z) const;
239 
240  void getWorldGravity(::rl::math::Vector& xyz) const;
241 
252  void inverseDynamics();
253 
254  void inverseForce();
255 
280 
282 
284 
285  virtual void update();
286 
287  protected:
298 
309 
320 
331 
342 
343  private:
344 
345  };
346  }
347 }
348 
349 #endif // RL_MDL_DYNAMIC_H
rl::math::Matrix
::Eigen::Matrix< Real, ::Eigen::Dynamic, ::Eigen::Dynamic > Matrix
Definition: Matrix.h:42
rl::mdl::Dynamic::M
::rl::math::Matrix M
Joint space mass matrix.
Definition: Dynamic.h:330
rl::mdl::Dynamic::forwardDynamics
void forwardDynamics()
Forward dynamics via articulated-body algorithm.
Definition: Dynamic.cpp:210
rl::mdl::Dynamic::update
virtual void update()
Definition: Dynamic.cpp:362
rl::mdl::Dynamic::getOperationalMassMatrixInverse
const ::rl::math::Matrix & getOperationalMassMatrixInverse() const
Access calculated operational space mass matrix inverse.
Definition: Dynamic.cpp:253
rl::mdl::Dynamic::Dynamic
Dynamic()
Definition: Dynamic.cpp:45
rl::mdl::Dynamic::setWorldGravity
void setWorldGravity(const ::rl::math::Real &x, const ::rl::math::Real &y, const ::rl::math::Real &z)
Definition: Dynamic.cpp:350
rl::mdl::Dynamic::getGravity
const ::rl::math::Vector & getGravity() const
Access calculated gravity vector.
Definition: Dynamic.cpp:235
rl::mdl::Kinematic
Definition: Kinematic.h:39
rl::mdl::Dynamic::calculateCentrifugalCoriolis
void calculateCentrifugalCoriolis()
Calculate centrifugal and Coriolis vector.
Definition: Dynamic.cpp:60
rl::mdl::Dynamic::calculateOperationalMassMatrixInverse
void calculateOperationalMassMatrixInverse()
Calculate operational space mass matrix inverse.
Definition: Dynamic.cpp:171
rl::math::Vector
::Eigen::Matrix< Real, ::Eigen::Dynamic, 1 > Vector
Definition: Vector.h:42
rl::mdl::Kinematic::J
::rl::math::Matrix J
Jacobian matrix.
Definition: Kinematic.h:262
rl::mdl::Dynamic::getCentrifugalCoriolis
const ::rl::math::Vector & getCentrifugalCoriolis() const
Access calculated centrifugal and Coriolis vector.
Definition: Dynamic.cpp:229
rl::mdl::Dynamic::getMassMatrix
const ::rl::math::Matrix & getMassMatrix() const
Access calculated joint space mass matrix.
Definition: Dynamic.cpp:247
rl::mdl::Dynamic::V
::rl::math::Vector V
Centrifugal and Coriolis vector.
Definition: Dynamic.h:341
rl::mdl::Dynamic::getMassMatrixInverse
const ::rl::math::Matrix & getMassMatrixInverse() const
Access calculated joint space mass matrix inverse.
Definition: Dynamic.cpp:241
rl::mdl::Model
Definition: Model.h:56
rl::mdl::Dynamic::calculateMassMatrix
void calculateMassMatrix()
Calculate joint space mass matrix.
Definition: Dynamic.cpp:103
rl::mdl::Dynamic::inverseDynamics
void inverseDynamics()
Inverse dynamics via recursive Newton-Euler algorithm.
Definition: Dynamic.cpp:271
rl::mdl::Dynamic::getWorldGravity
void getWorldGravity(::rl::math::Real &x, ::rl::math::Real &y, ::rl::math::Real &z) const
Definition: Dynamic.cpp:259
rl::mdl::Dynamic::G
::rl::math::Vector G
Gravity vector.
Definition: Dynamic.h:297
rl::mdl::Dynamic
Definition: Dynamic.h:37
rl::mdl::Dynamic::clone
Model * clone() const
Definition: Dynamic.cpp:183
rl::mdl::Dynamic::eulerCauchy
void eulerCauchy(const ::rl::math::Real &dt)
Integration via Euler-Cauchy.
Definition: Dynamic.cpp:189
rl::mdl::Dynamic::calculateGravity
void calculateGravity()
Calculate gravity vector.
Definition: Dynamic.cpp:84
rl::mdl::Dynamic::~Dynamic
virtual ~Dynamic()
Definition: Dynamic.cpp:55
rl::mdl::Dynamic::rungeKuttaNystrom
void rungeKuttaNystrom(const ::rl::math::Real &dt)
Integration via Runge-Kutta-Nyström.
Definition: Dynamic.cpp:294
rl::math::Real
double Real
Definition: Real.h:42
rl::mdl::Dynamic::calculateMassMatrixInverse
void calculateMassMatrixInverse()
Calculate joint space mass matrix inverse.
Definition: Dynamic.cpp:137
rl::mdl::Dynamic::invM
::rl::math::Matrix invM
Joint space mass matrix inverse.
Definition: Dynamic.h:308
rl::mdl::Dynamic::invMx
::rl::math::Matrix invMx
Operational space mass matrix inverse.
Definition: Dynamic.h:319
rl::mdl::Dynamic::inverseForce
void inverseForce()
Definition: Dynamic.cpp:285
Kinematic.h
rl
Robotics Library.
Definition: AnalogInput.cpp:30