Rigid Body Dynamics Library
Dynamics.h
Go to the documentation of this file.
1/*
2 * RBDL - Rigid Body Dynamics Library
3 * Copyright (c) 2011-2018 Martin Felis <martin@fysx.org>
4 *
5 * Licensed under the zlib license. See LICENSE for more details.
6 */
7
8#ifndef RBDL_DYNAMICS_H
9#define RBDL_DYNAMICS_H
10
11#include <assert.h>
12#include <iostream>
13
14#include "rbdl/rbdl_math.h"
15#include "rbdl/rbdl_mathutils.h"
16
17#include "rbdl/Logging.h"
18
19namespace RigidBodyDynamics {
20
21struct Model;
22
45RBDL_DLLAPI void InverseDynamics (
46 Model &model,
47 const Math::VectorNd &Q,
48 const Math::VectorNd &QDot,
49 const Math::VectorNd &QDDot,
50 Math::VectorNd &Tau,
51 std::vector<Math::SpatialVector> *f_ext = NULL
52 );
53
66RBDL_DLLAPI void NonlinearEffects (
67 Model &model,
68 const Math::VectorNd &Q,
69 const Math::VectorNd &QDot,
70 Math::VectorNd &Tau,
71 std::vector<Math::SpatialVector> *f_ext = NULL
72 );
73
90 Model& model,
91 const Math::VectorNd &Q,
93 bool update_kinematics = true
94 );
95
111RBDL_DLLAPI void ForwardDynamics (
112 Model &model,
113 const Math::VectorNd &Q,
114 const Math::VectorNd &QDot,
115 const Math::VectorNd &Tau,
116 Math::VectorNd &QDDot,
117 std::vector<Math::SpatialVector> *f_ext = NULL
118 );
119
139 Model &model,
140 const Math::VectorNd &Q,
141 const Math::VectorNd &QDot,
142 const Math::VectorNd &Tau,
143 Math::VectorNd &QDDot,
144 Math::LinearSolver linear_solver = Math::LinearSolverColPivHouseholderQR,
145 std::vector<Math::SpatialVector> *f_ext = NULL,
146 Math::MatrixNd *H = NULL,
147 Math::VectorNd *C = NULL
148 );
149
171RBDL_DLLAPI void CalcMInvTimesTau (
172 Model &model,
173 const Math::VectorNd &Q,
174 const Math::VectorNd &Tau,
175 Math::VectorNd &QDDot,
176 bool update_kinematics=true
177 );
178
181}
182
183/* RBDL_DYNAMICS_H */
184#endif
RBDL_DLLAPI void InverseDynamics(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot, Math::VectorNd &Tau, std::vector< Math::SpatialVector > *f_ext=NULL)
Computes inverse dynamics with the Newton-Euler Algorithm.
RBDL_DLLAPI void CalcMInvTimesTau(Model &model, const Math::VectorNd &Q, const Math::VectorNd &Tau, Math::VectorNd &QDDot, bool update_kinematics=true)
Computes the effect of multiplying the inverse of the joint space inertia matrix with a vector in lin...
RBDL_DLLAPI void NonlinearEffects(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, std::vector< Math::SpatialVector > *f_ext=NULL)
Computes the coriolis forces.
RBDL_DLLAPI void ForwardDynamicsLagrangian(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, Math::VectorNd &QDDot, Math::LinearSolver linear_solver=Math::LinearSolverColPivHouseholderQR, std::vector< Math::SpatialVector > *f_ext=NULL, Math::MatrixNd *H=NULL, Math::VectorNd *C=NULL)
Computes forward dynamics by building and solving the full Lagrangian equation.
RBDL_DLLAPI void ForwardDynamics(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, Math::VectorNd &QDDot, std::vector< Math::SpatialVector > *f_ext=NULL)
Computes forward dynamics with the Articulated Body Algorithm.
RBDL_DLLAPI void CompositeRigidBodyAlgorithm(Model &model, const Math::VectorNd &Q, Math::MatrixNd &H, bool update_kinematics=true)
Computes the joint space inertia matrix by using the Composite Rigid Body Algorithm.
LinearSolverColPivHouseholderQR