parallel-geometry.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021 INRIA
3 //
4 
5 #include <iostream>
6 
7 #include "pinocchio/multibody/geometry.hpp"
8 #include "pinocchio/algorithm/parallel/geometry.hpp"
9 #include "pinocchio/parsers/urdf.hpp"
10 #include "pinocchio/parsers/srdf.hpp"
11 
12 #include <vector>
13 #include <boost/test/unit_test.hpp>
14 
15 using namespace pinocchio;
16 
17 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
18 
20 {
21  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
22 
25  Data data(model);
26 
27  const std::string package_path = PINOCCHIO_MODEL_DIR;
28  hpp::fcl::MeshLoaderPtr mesh_loader = boost::make_shared<hpp::fcl::CachedMeshLoader>();
29  const std::string srdf_filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/srdf/talos.srdf");
30  std::vector<std::string> package_paths(1,package_path);
31  pinocchio::GeometryModel geometry_model;
32  pinocchio::urdf::buildGeom(model,filename,COLLISION,geometry_model,package_paths,mesh_loader);
33 
34 
35  const int num_thread = omp_get_max_threads();
36  GeometryPool pool(model,pinocchio::GeometryModel(),num_thread);
37 
38  pool.update(geometry_model);
39  BOOST_CHECK(pool.geometry_model() == geometry_model);
40  pool.update(GeometryData(geometry_model));
41 
42  pool.update(geometry_model,GeometryData(geometry_model));
43 }
44 
46 {
47  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
48 
51  Data data(model), data_ref(model);
52 
53  const std::string package_path = PINOCCHIO_MODEL_DIR;
54  hpp::fcl::MeshLoaderPtr mesh_loader = boost::make_shared<hpp::fcl::CachedMeshLoader>();
55  const std::string srdf_filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/srdf/talos.srdf");
56  std::vector<std::string> package_paths(1,package_path);
57  pinocchio::GeometryModel geometry_model;
58  pinocchio::urdf::buildGeom(model,filename,COLLISION,geometry_model,package_paths,mesh_loader);
59 
60  geometry_model.addAllCollisionPairs();
61  pinocchio::srdf::removeCollisionPairs(model,geometry_model,srdf_filename,false);
62 
63  GeometryData geometry_data(geometry_model), geometry_data_ref(geometry_model);
64 
65  const Eigen::VectorXd qmax = Eigen::VectorXd::Ones(model.nq);
66  Eigen::VectorXd q = randomConfiguration(model,-qmax,qmax);
67 
68  const bool res_ref = computeCollisions(model,data_ref,geometry_model,geometry_data_ref,q);
69  const bool res = computeCollisions(model,data,geometry_model,geometry_data,q);
70 
71  BOOST_CHECK(res_ref == res);
72  BOOST_CHECK(geometry_data_ref.collisionPairIndex == geometry_data.collisionPairIndex);
73 
74  for(size_t k = 0; k < geometry_model.collisionPairs.size(); ++k)
75  {
76  const CollisionPair & cp = geometry_model.collisionPairs[k];
77  BOOST_CHECK(geometry_data_ref.oMg[cp.first] == geometry_data.oMg[cp.first]);
78  BOOST_CHECK(geometry_data_ref.oMg[cp.second] == geometry_data.oMg[cp.second]);
79  BOOST_CHECK( geometry_data_ref.collisionResults[k].getContacts()
80  == geometry_data.collisionResults[k].getContacts());
81  }
82 }
83 
84 BOOST_AUTO_TEST_CASE(test_pool_talos)
85 {
86  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
87 
90  Data data_ref(model);
91 
92  const std::string package_path = PINOCCHIO_MODEL_DIR;
93  hpp::fcl::MeshLoaderPtr mesh_loader = boost::make_shared<hpp::fcl::CachedMeshLoader>();
94  const std::string srdf_filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/srdf/talos.srdf");
95  std::vector<std::string> package_paths(1,package_path);
96  pinocchio::GeometryModel geometry_model;
97  pinocchio::urdf::buildGeom(model,filename,COLLISION,geometry_model,package_paths,mesh_loader);
98 
99  geometry_model.addAllCollisionPairs();
100  pinocchio::srdf::removeCollisionPairs(model,geometry_model,srdf_filename,false);
101 
102  GeometryData geometry_data_ref(geometry_model);
103 
104  const Eigen::VectorXd qmax = Eigen::VectorXd::Ones(model.nq);
105  const Eigen::DenseIndex batch_size = 128;
106  const int num_thread = omp_get_max_threads();
107 
108  Eigen::MatrixXd q(model.nq,batch_size);
109  for(Eigen::DenseIndex i = 0; i < batch_size; ++i)
110  {
111  q.col(i) = randomConfiguration(model,-qmax,qmax);
112  }
113 
114  typedef Eigen::Matrix<bool,Eigen::Dynamic,1> VectorXb;
115  VectorXb res(batch_size); res.fill(false);
116  VectorXb res_ref(batch_size); res_ref.fill(false);
117  for(Eigen::DenseIndex i = 0; i < batch_size; ++i)
118  {
119  res_ref[i] = computeCollisions(model,data_ref,geometry_model,geometry_data_ref,q.col(i));
120  }
121 
122  GeometryPool pool(model,geometry_model,num_thread);
123  computeCollisions(num_thread,pool,q,res);
124 
125  BOOST_CHECK(res == res_ref);
126 }
127 
128 BOOST_AUTO_TEST_SUITE_END()
const GeometryModel & geometry_model() const
Returns the geometry model.
void removeCollisionPairs(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, GeometryModel &geom_model, const std::string &filename, const bool verbose=false)
Deactive all possible collision pairs mentioned in the SRDF file. It throws if the SRDF file is incor...
CollisionPairVector collisionPairs
Vector of collision pairs.
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
data
#define PINOCCHIO_MODEL_DIR
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
bool computeCollisions(const int num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false)
Eigen::Matrix< bool, Eigen::Dynamic, 1 > VectorXb
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(),::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...
void addAllCollisionPairs()
Add all possible collision pairs.
string srdf_filename
Definition: collisions.py:25
Main pinocchio namespace.
Definition: timings.cpp:30
res
JointModelFreeFlyerTpl< double > JointModelFreeFlyer
void update(const GeometryData &geometry_data)
Update the geometry datas with the new value.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:14
JointCollectionTpl & model
int nq
Dimension of the configuration vector representation.
BOOST_AUTO_TEST_CASE(test_pool)


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:04