1 #ifndef MODERN_ROBOTICS__ROBOT_CONTROL_HPP___
2 #define MODERN_ROBOTICS__ROBOT_CONTROL_HPP___
31 const arma::vec & thetalist,
32 const arma::vec & dthetalist,
33 const arma::vec & eint,
35 const std::vector<arma::mat44> & Mlist,
36 const std::vector<arma::mat66> & Glist,
37 const std::vector<arma::vec6> & Slist,
38 const arma::vec & thetalistd,
39 const arma::vec & dthetalistd,
40 const arma::vec & ddthetalistd,
81 const std::tuple<std::vector<arma::vec>, std::vector<arma::vec>>
83 const arma::vec & thetalist,
84 const arma::vec & dthetalist,
86 const std::vector<arma::vec6> & Ftipmat,
87 const std::vector<arma::mat44> & Mlist,
88 const std::vector<arma::mat66> & Glist,
89 const std::vector<arma::vec6> & Slist,
90 const std::vector<arma::vec> & thetamatd,
91 const std::vector<arma::vec> & dthetamatd,
92 const std::vector<arma::vec> & ddthetamatd,
93 const arma::vec3 & gtilde,
94 const std::vector<arma::mat44> & Mtildelist,
95 const std::vector<arma::mat66> & Gtildelist,
const arma::vec ComputeTorque(const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec &eint, const arma::vec3 &g, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist, const arma::vec &thetalistd, const arma::vec &dthetalistd, const arma::vec &ddthetalistd, const double kp, const double ki, const double kd)
Computes the joint control torques at a particular time instant.
Definition: robot_control.cpp:6
const std::tuple< std::vector< arma::vec >, std::vector< arma::vec > > SimulateControl(const arma::vec &thetalist, const arma::vec &dthetalist, 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 std::vector< arma::vec > &thetamatd, const std::vector< arma::vec > &dthetamatd, const std::vector< arma::vec > &ddthetamatd, const arma::vec3 >ilde, const std::vector< arma::mat44 > &Mtildelist, const std::vector< arma::mat66 > &Gtildelist, const double kp, const double ki, const double kd, const double dt, const size_t intRes)
Simulates the computed torque controller over a given desired trajectory.
Definition: dynamics_of_open_chains.hpp:7