forked from stack-of-tasks/pinocchio
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathinverse-dynamics-derivatives.cpp
More file actions
42 lines (31 loc) · 1.62 KB
/
inverse-dynamics-derivatives.cpp
File metadata and controls
42 lines (31 loc) · 1.62 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
#include "pinocchio/parsers/urdf.hpp"
#include "pinocchio/algorithm/joint-configuration.hpp"
#include "pinocchio/algorithm/rnea-derivatives.hpp"
#include <iostream>
// PINOCCHIO_MODEL_DIR is defined by the CMake but you can define your own directory here.
#ifndef PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR "path_to_the_model_dir"
#endif
int main(int argc, char ** argv)
{
using namespace pinocchio;
// You should change here to set up your own URDF file or just pass it as an argument of this example.
const std::string urdf_filename = (argc<=1) ? PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/ur_description/urdf/ur5_robot.urdf") : argv[1];
// Load the URDF model
Model model;
pinocchio::urdf::buildModel(urdf_filename,model);
// Build a data related to model
Data data(model);
// Sample a random joint configuration as well as random joint velocity and acceleration
Eigen::VectorXd q = randomConfiguration(model);
Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv);
// Allocate result container
Eigen::MatrixXd djoint_torque_dq = Eigen::MatrixXd::Zero(model.nv,model.nv);
Eigen::MatrixXd djoint_torque_dv = Eigen::MatrixXd::Zero(model.nv,model.nv);
Eigen::MatrixXd djoint_torque_da = Eigen::MatrixXd::Zero(model.nv,model.nv);
// Computes the inverse dynamics (RNEA) derivatives for all the joints of the robot
computeRNEADerivatives(model, data, q, v, a, djoint_torque_dq, djoint_torque_dv, djoint_torque_da);
// Get access to the joint torque
std::cout << "Joint torque: " << data.tau.transpose() << std::endl;
}