Directory: | ./ |
---|---|
File: | examples/forward-dynamics-derivatives.cpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 15 | 15 | 100.0% |
Branches: | 25 | 58 | 43.1% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | #include "pinocchio/parsers/urdf.hpp" | ||
2 | |||
3 | #include "pinocchio/algorithm/joint-configuration.hpp" | ||
4 | #include "pinocchio/algorithm/aba-derivatives.hpp" | ||
5 | |||
6 | #include <iostream> | ||
7 | |||
8 | // PINOCCHIO_MODEL_DIR is defined by the CMake but you can define your own directory here. | ||
9 | #ifndef PINOCCHIO_MODEL_DIR | ||
10 | #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir" | ||
11 | #endif | ||
12 | |||
13 | 1 | int main(int argc, char ** argv) | |
14 | { | ||
15 | using namespace pinocchio; | ||
16 | |||
17 | // You should change here to set up your own URDF file or just pass it as an argument of this | ||
18 | // example. | ||
19 | const std::string urdf_filename = | ||
20 | (argc <= 1) ? PINOCCHIO_MODEL_DIR | ||
21 |
2/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
|
2 | + std::string("/example-robot-data/robots/ur_description/urdf/ur5_robot.urdf") |
22 |
4/12✓ Branch 0 taken 1 times.
✗ Branch 1 not taken.
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✓ Branch 10 taken 1 times.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✗ Branch 13 not taken.
✗ Branch 14 not taken.
|
2 | : argv[1]; |
23 | |||
24 | // Load the URDF model | ||
25 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | Model model; |
26 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | pinocchio::urdf::buildModel(urdf_filename, model); |
27 | |||
28 | // Build a data related to model | ||
29 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | Data data(model); |
30 | |||
31 | // Sample a random joint configuration as well as random joint velocity and torque | ||
32 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | Eigen::VectorXd q = randomConfiguration(model); |
33 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv); |
34 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | Eigen::VectorXd tau = Eigen::VectorXd::Zero(model.nv); |
35 | |||
36 | // Allocate result container | ||
37 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | Eigen::MatrixXd djoint_acc_dq = Eigen::MatrixXd::Zero(model.nv, model.nv); |
38 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | Eigen::MatrixXd djoint_acc_dv = Eigen::MatrixXd::Zero(model.nv, model.nv); |
39 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | Eigen::MatrixXd djoint_acc_dtau = Eigen::MatrixXd::Zero(model.nv, model.nv); |
40 | |||
41 | // Computes the forward dynamics (ABA) derivatives for all the joints of the robot | ||
42 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | computeABADerivatives(model, data, q, v, tau, djoint_acc_dq, djoint_acc_dv, djoint_acc_dtau); |
43 | |||
44 | // Get access to the joint acceleration | ||
45 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
1 | std::cout << "Joint acceleration: " << data.ddq.transpose() << std::endl; |
46 | 1 | } | |
47 |