| Directory: | ./ |
|---|---|
| File: | examples/geometry-models.cpp |
| Date: | 2025-02-12 21:03:38 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 32 | 32 | 100.0% |
| Branches: | 67 | 136 | 49.3% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | #include "pinocchio/multibody/fcl.hpp" | ||
| 2 | #include "pinocchio/parsers/urdf.hpp" | ||
| 3 | |||
| 4 | #include "pinocchio/algorithm/joint-configuration.hpp" | ||
| 5 | #include "pinocchio/algorithm/kinematics.hpp" | ||
| 6 | #include "pinocchio/algorithm/geometry.hpp" | ||
| 7 | |||
| 8 | #include <iostream> | ||
| 9 | |||
| 10 | // PINOCCHIO_MODEL_DIR is defined by the CMake but you can define your own directory here. | ||
| 11 | #ifndef PINOCCHIO_MODEL_DIR | ||
| 12 | #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir" | ||
| 13 | #endif | ||
| 14 | |||
| 15 | 1 | int main(int argc, char ** argv) | |
| 16 | { | ||
| 17 | using namespace pinocchio; | ||
| 18 | |||
| 19 | const std::string model_path = | ||
| 20 |
6/20✓ Branch 0 taken 1 times.
✗ Branch 1 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✗ Branch 11 not taken.
✗ Branch 12 not taken.
✗ Branch 13 not taken.
✓ Branch 14 taken 1 times.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 19 not taken.
✗ Branch 20 not taken.
✗ Branch 21 not taken.
✗ Branch 22 not taken.
✗ Branch 23 not taken.
✗ Branch 24 not taken.
|
2 | (argc <= 1) ? PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots") : argv[1]; |
| 21 |
2/4✗ Branch 1 not taken.
✓ Branch 2 taken 1 times.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | const std::string mesh_dir = (argc <= 1) ? PINOCCHIO_MODEL_DIR : argv[1]; |
| 22 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | const std::string urdf_filename = model_path + "/ur_description/urdf/ur5_robot.urdf"; |
| 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 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | GeometryModel collision_model; |
| 28 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
1 | pinocchio::urdf::buildGeom(model, urdf_filename, COLLISION, collision_model, mesh_dir); |
| 29 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | GeometryModel visual_model; |
| 30 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
1 | pinocchio::urdf::buildGeom(model, urdf_filename, VISUAL, visual_model, mesh_dir); |
| 31 |
3/6✓ 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.
|
1 | std::cout << "model name: " << model.name << std::endl; |
| 32 | |||
| 33 | // Create data required by the algorithms | ||
| 34 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | Data data(model); |
| 35 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | GeometryData collision_data(collision_model); |
| 36 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | GeometryData visual_data(visual_model); |
| 37 | |||
| 38 | // Sample a random configuration | ||
| 39 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | Eigen::VectorXd q = randomConfiguration(model); |
| 40 |
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 << "q: " << q.transpose() << std::endl; |
| 41 | |||
| 42 | // Perform the forward kinematics over the kinematic tree | ||
| 43 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | forwardKinematics(model, data, q); |
| 44 | |||
| 45 | // Update Geometry models | ||
| 46 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | updateGeometryPlacements(model, data, collision_model, collision_data); |
| 47 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | updateGeometryPlacements(model, data, visual_model, visual_data); |
| 48 | |||
| 49 | // Print out the placement of each joint of the kinematic tree | ||
| 50 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | std::cout << "\nJoint placements:" << std::endl; |
| 51 |
2/2✓ Branch 0 taken 7 times.
✓ Branch 1 taken 1 times.
|
8 | for (JointIndex joint_id = 0; joint_id < (JointIndex)model.njoints; ++joint_id) |
| 52 |
5/10✓ Branch 2 taken 7 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 7 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 7 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 7 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 7 times.
✗ Branch 16 not taken.
|
7 | std::cout << std::setw(24) << std::left << model.names[joint_id] << ": " << std::fixed |
| 53 |
5/10✓ Branch 2 taken 7 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 7 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 7 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 7 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 7 times.
✗ Branch 16 not taken.
|
7 | << std::setprecision(2) << data.oMi[joint_id].translation().transpose() << std::endl; |
| 54 | |||
| 55 | // Print out the placement of each collision geometry object | ||
| 56 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | std::cout << "\nCollision object placements:" << std::endl; |
| 57 |
2/2✓ Branch 0 taken 8 times.
✓ Branch 1 taken 1 times.
|
9 | for (GeomIndex geom_id = 0; geom_id < (GeomIndex)collision_model.ngeoms; ++geom_id) |
| 58 |
4/8✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 8 times.
✗ Branch 8 not taken.
✓ Branch 11 taken 8 times.
✗ Branch 12 not taken.
|
8 | std::cout << geom_id << ": " << std::fixed << std::setprecision(2) |
| 59 |
4/8✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 8 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 8 times.
✗ Branch 12 not taken.
|
8 | << collision_data.oMg[geom_id].translation().transpose() << std::endl; |
| 60 | |||
| 61 | // Print out the placement of each visual geometry object | ||
| 62 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | std::cout << "\nVisual object placements:" << std::endl; |
| 63 |
2/2✓ Branch 0 taken 7 times.
✓ Branch 1 taken 1 times.
|
8 | for (GeomIndex geom_id = 0; geom_id < (GeomIndex)visual_model.ngeoms; ++geom_id) |
| 64 |
4/8✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 7 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 7 times.
✗ Branch 8 not taken.
✓ Branch 11 taken 7 times.
✗ Branch 12 not taken.
|
7 | std::cout << geom_id << ": " << std::fixed << std::setprecision(2) |
| 65 |
4/8✓ Branch 2 taken 7 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 7 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 7 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 7 times.
✗ Branch 12 not taken.
|
7 | << visual_data.oMg[geom_id].translation().transpose() << std::endl; |
| 66 | 1 | } | |
| 67 |