1 #ifndef MODERN_ROBOTICS__DYNAMICS_OF_OPEN_CHAINS___
2 #define MODERN_ROBOTICS__DYNAMICS_OF_OPEN_CHAINS___
14 const arma::mat66
ad(
const arma::vec6 & V);
17 const arma::vec & thetalist,
18 const arma::vec & dthetalist,
19 const arma::vec & ddthetalist,
21 const arma::vec6 & Ftip,
22 const std::vector<arma::mat44> & Mlist,
23 const std::vector<arma::mat66> & Glist,
24 const std::vector<arma::vec6> & Slist
43 const arma::vec & thetalist,
44 const std::vector<arma::mat44> & Mlist,
45 const std::vector<arma::mat66> & Glist,
46 const std::vector<arma::vec6> & Slist
63 const arma::vec & thetalist,
64 const arma::vec & dthetalist,
65 const std::vector<arma::mat44> Mlist,
66 const std::vector<arma::mat66> & Glist,
67 const std::vector<arma::vec6> & Slist
83 const arma::vec & thetalist,
85 const std::vector<arma::mat44> & Mlist,
86 const std::vector<arma::mat66> & Glist,
87 const std::vector<arma::vec6> & Slist
102 const arma::vec & thetalist,
103 const arma::vec6 & Ftip,
104 const std::vector<arma::mat44> & Mlist,
105 const std::vector<arma::mat66> & Glist,
106 const std::vector<arma::vec6> & Slist
124 const arma::vec & thetalist,
125 const arma::vec & dthetalist,
126 const arma::vec & taulist,
127 const arma::vec3 & g,
128 const arma::vec6 & Ftip,
129 const std::vector<arma::mat44> & Mlist,
130 const std::vector<arma::mat66> & Glist,
131 const std::vector<arma::vec6> & Slist
143 const std::tuple<const arma::vec, const arma::vec>
EulerStep(
144 const arma::vec & thetalist,
145 const arma::vec & dthetalist,
146 const arma::vec & ddthetalist,
159 const std::tuple<const arma::vec, const arma::vec>
RK4Step(
160 const arma::vec & thetalist,
161 const arma::vec & dthetalist,
192 const std::vector<arma::vec> & thetamat,
193 const std::vector<arma::vec> & dthetamat,
194 const std::vector<arma::vec> & ddthetamat,
195 const arma::vec3 & g,
196 const std::vector<arma::vec6> & Ftipmat,
197 const std::vector<arma::mat44> & Mlist,
198 const std::vector<arma::mat66> & Glist,
199 const std::vector<arma::vec6> & Slist
225 const std::tuple<const std::vector<arma::vec>,
const std::vector<arma::vec>>
227 const arma::vec & thetalist,
228 const arma::vec & dthetalist,
229 const std::vector<arma::vec> & taumat,
230 const arma::vec3 & g,
231 const std::vector<arma::vec6> & Ftipmat,
232 const std::vector<arma::mat44> & Mlist,
233 const std::vector<arma::mat66> & Glist,
234 const std::vector<arma::vec6> & Slist,
const arma::vec GravityForces(const arma::vec &thetalist, const arma::vec3 &g, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist)
Computes the joint forces/torques an open chain robot requires to overcome gravity at its configurati...
Definition: dynamics_of_open_chains.cpp:145
const arma::vec EndEffectorForces(const arma::vec &thetalist, const arma::vec6 &Ftip, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist)
Computes the joint forces/torques an open chain robot requires only to create the end-effector force ...
Definition: dynamics_of_open_chains.cpp:170
const std::tuple< const arma::vec, const arma::vec > RK4Step(const arma::vec &thetalist, const arma::vec &dthetalist, const std::function< const std::tuple< const arma::vec, const arma::vec >(const arma::vec &, const arma::vec &) > &f, const double dt)
Compute the joint angles and velocities at the next timestep using Runge–Kutta methods integration.
Definition: dynamics_of_open_chains.cpp:230
const std::vector< arma::vec > InverseDynamicsTrajectory(const std::vector< arma::vec > &thetamat, const std::vector< arma::vec > &dthetamat, const std::vector< arma::vec > &ddthetamat, const arma::vec3 &g, const std::vector< arma::vec6 > &Ftipmat, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist)
Calculates the joint forces/torques required to move the serial chain along the given trajectory usin...
Definition: dynamics_of_open_chains.cpp:256
const std::tuple< const std::vector< arma::vec >, const std::vector< arma::vec > > ForwardDynamicsTrajectory(const arma::vec &thetalist, const arma::vec &dthetalist, const std::vector< arma::vec > &taumat, const arma::vec3 &g, const std::vector< arma::vec6 > &Ftipmat, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist, const double dt, const int intRes)
Simulates the motion of a serial chain given an open-loop history of joint forces/torques.
Definition: dynamics_of_open_chains.cpp:292
const arma::vec ForwardDynamics(const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec &taulist, const arma::vec3 &g, const arma::vec6 &Ftip, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist)
Computes forward dynamics in the space frame for an open chain robot.
Definition: dynamics_of_open_chains.cpp:195
const arma::mat MassMatrix(const arma::vec &thetalist, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist)
Computes the mass matrix of an open chain robot based on the given configuration.
Definition: dynamics_of_open_chains.cpp:86
const std::tuple< const arma::vec, const arma::vec > EulerStep(const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec &ddthetalist, const double dt)
Compute the joint angles and velocities at the next timestep using first order Euler integration.
Definition: dynamics_of_open_chains.cpp:217
const arma::vec VelQuandraticForces(const arma::vec &thetalist, const arma::vec &dthetalist, const std::vector< arma::mat44 > Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist)
Computes the Coriolis and centripetal terms in the inverse dynamics of an open chain robot.
Definition: dynamics_of_open_chains.cpp:120
Definition: dynamics_of_open_chains.hpp:7
const arma::mat66 ad(const arma::vec6 &V)
Calculate the 6x6 matrix [adV] of the given 6-vector.
Definition: dynamics_of_open_chains.cpp:8
const arma::vec InverseDynamics(const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec &ddthetalist, const arma::vec &g, const arma::vec6 &Ftip, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist)
Definition: dynamics_of_open_chains.cpp:21