forked from stack-of-tasks/pinocchio
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathgeometry-models.cpp
72 lines (59 loc) · 2.86 KB
/
geometry-models.cpp
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
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
#include "pinocchio/multibody/fcl.hpp"
#include "pinocchio/parsers/urdf.hpp"
#include "pinocchio/algorithm/joint-configuration.hpp"
#include "pinocchio/algorithm/kinematics.hpp"
#include "pinocchio/algorithm/geometry.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;
const std::string model_path = (argc<=1) ? PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots") : argv[1];
const std::string mesh_dir = (argc<=1) ? PINOCCHIO_MODEL_DIR : argv[1];
const std::string urdf_filename = model_path + "/ur_description/urdf/ur5_robot.urdf";
// Load the urdf model
Model model;
pinocchio::urdf::buildModel(urdf_filename,model);
GeometryModel collision_model;
pinocchio::urdf::buildGeom(model, urdf_filename, COLLISION, collision_model, mesh_dir);
GeometryModel visual_model;
pinocchio::urdf::buildGeom(model, urdf_filename, VISUAL, visual_model, mesh_dir);
std::cout << "model name: " << model.name << std::endl;
// Create data required by the algorithms
Data data(model);
GeometryData collision_data(collision_model);
GeometryData visual_data(visual_model);
// Sample a random configuration
Eigen::VectorXd q = randomConfiguration(model);
std::cout << "q: " << q.transpose() << std::endl;
// Perform the forward kinematics over the kinematic tree
forwardKinematics(model,data,q);
// Update Geometry models
updateGeometryPlacements(model, data, collision_model, collision_data);
updateGeometryPlacements(model, data, visual_model, visual_data);
// Print out the placement of each joint of the kinematic tree
std::cout << "\nJoint placements:" << std::endl;
for(JointIndex joint_id = 0; joint_id < (JointIndex)model.njoints; ++joint_id)
std::cout << std::setw(24) << std::left
<< model.names[joint_id] << ": "
<< std::fixed << std::setprecision(2)
<< data.oMi[joint_id].translation().transpose()
<< std::endl;
// Print out the placement of each collision geometry object
std::cout << "\nCollision object placements:" << std::endl;
for(GeomIndex geom_id = 0; geom_id < (GeomIndex)collision_model.ngeoms; ++geom_id)
std::cout << geom_id << ": "
<< std::fixed << std::setprecision(2)
<< collision_data.oMg[geom_id].translation().transpose()
<< std::endl;
// Print out the placement of each visual geometry object
std::cout << "\nVisual object placements:" << std::endl;
for(GeomIndex geom_id = 0; geom_id < (GeomIndex)visual_model.ngeoms; ++geom_id)
std::cout << geom_id << ": "
<< std::fixed << std::setprecision(2)
<< visual_data.oMg[geom_id].translation().transpose()
<< std::endl;
}