collision/parallel/geometry.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021-2024 INRIA
3 //
4 
5 #ifndef __pinocchio_collision_parallel_geometry_hpp__
6 #define __pinocchio_collision_parallel_geometry_hpp__
7 
12 
13 #include <cstdint>
14 
15 namespace pinocchio
16 {
17 
19  const size_t num_threads,
20  const GeometryModel & geom_model,
22  const bool stopAtFirstCollision = false)
23  {
24  bool is_colliding = false;
25 
27  const int64_t batch_size = static_cast<int64_t>(geom_model.collisionPairs.size());
28  int64_t omp_cp_index = 0;
29  // Visual studio support OpenMP 2 that only support signed indexes in for loops
30  // See
31  // https://stackoverflow.com/questions/2820621/why-arent-unsigned-openmp-index-variables-allowed
32  // -openmp:llvm could solve this:
33  // https://learn.microsoft.com/en-us/cpp/build/reference/openmp-enable-openmp-2-0-support?view=msvc-160
34 #pragma omp parallel for schedule(dynamic)
35  for (omp_cp_index = 0; omp_cp_index < batch_size; ++omp_cp_index)
36  {
37  size_t cp_index = static_cast<size_t>(omp_cp_index);
38 
39  if (stopAtFirstCollision && is_colliding)
40  continue;
41 
42  const CollisionPair & collision_pair = geom_model.collisionPairs[cp_index];
43 
44  if (
45  geom_data.activeCollisionPairs[cp_index]
46  && !(
47  geom_model.geometryObjects[collision_pair.first].disableCollision
48  || geom_model.geometryObjects[collision_pair.second].disableCollision))
49  {
50  bool res = computeCollision(geom_model, geom_data, cp_index);
51  if (!is_colliding && res)
52  {
53  is_colliding = true;
54  geom_data.collisionPairIndex = cp_index; // first pair to be in collision
55  }
56  }
57  }
58 
59  return is_colliding;
60  }
61 
62  template<
63  typename Scalar,
64  int Options,
65  template<typename, int>
66  class JointCollectionTpl,
67  typename ConfigVectorType>
69  const size_t num_threads,
72  const GeometryModel & geom_model,
74  const Eigen::MatrixBase<ConfigVectorType> & q,
75  const bool stopAtFirstCollision = false)
76  {
78  return computeCollisionsInParallel(num_threads, geom_model, geom_data, stopAtFirstCollision);
79  }
80 
81  template<
82  typename Scalar,
83  int Options,
84  template<typename, int>
85  class JointCollectionTpl,
86  typename ConfigVectorPool,
87  typename CollisionVectorResult>
89  const size_t num_threads,
91  const Eigen::MatrixBase<ConfigVectorPool> & q,
92  const Eigen::MatrixBase<CollisionVectorResult> & res,
93  const bool stopAtFirstCollisionInConfiguration = false,
94  const bool stopAtFirstCollisionInBatch = false)
95  {
97  typedef typename Pool::Model Model;
98  typedef typename Pool::Data Data;
99  typedef typename Pool::GeometryModel GeometryModel;
100  typedef typename Pool::GeometryData GeometryData;
101  typedef typename Pool::ModelVector ModelVector;
102  typedef typename Pool::DataVector DataVector;
103  typedef typename Pool::GeometryModelVector GeometryModelVector;
104  typedef typename Pool::GeometryDataVector GeometryDataVector;
105 
106  PINOCCHIO_CHECK_INPUT_ARGUMENT(pool.size() > 0, "The pool should have at least one element");
107  PINOCCHIO_CHECK_INPUT_ARGUMENT(num_threads <= pool.size(), "The pool is too small");
108 
109  const ModelVector & models = pool.getModels();
110  const Model & model_check = models[0];
111  const GeometryModelVector & geometry_models = pool.getGeometryModels();
112  DataVector & datas = pool.getDatas();
113  GeometryDataVector & geometry_datas = pool.getGeometryDatas();
114  CollisionVectorResult & res_ = res.const_cast_derived();
115 
116  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.rows(), model_check.nq);
117  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), res.size());
118  res_.fill(false);
119 
121  const Eigen::DenseIndex batch_size = res.size();
122 
123  if (stopAtFirstCollisionInBatch)
124  {
125  bool is_colliding = false;
126  Eigen::DenseIndex i = 0;
127 #pragma omp parallel for schedule(static)
128  for (i = 0; i < batch_size; i++)
129  {
130  if (is_colliding)
131  continue;
132 
133  const int thread_id = omp_get_thread_num();
134 
135  const Model & model = models[(size_t)thread_id];
136  Data & data = datas[(size_t)thread_id];
137  const GeometryModel & geometry_model = geometry_models[(size_t)thread_id];
138  GeometryData & geometry_data = geometry_datas[(size_t)thread_id];
139  res_[i] = computeCollisions(
140  model, data, geometry_model, geometry_data, q.col(i),
141  stopAtFirstCollisionInConfiguration);
142 
143  if (res_[i])
144  {
145  is_colliding = true;
146  }
147  }
148  }
149  else
150  {
151  Eigen::DenseIndex i = 0;
152 #pragma omp parallel for schedule(static)
153  for (i = 0; i < batch_size; i++)
154  {
155  const int thread_id = omp_get_thread_num();
156 
157  const Model & model = models[(size_t)thread_id];
158  Data & data = datas[(size_t)thread_id];
159  const GeometryModel & geometry_model = geometry_models[(size_t)thread_id];
160  GeometryData & geometry_data = geometry_datas[(size_t)thread_id];
161  res_[i] = computeCollisions(
162  model, data, geometry_model, geometry_data, q.col(i),
163  stopAtFirstCollisionInConfiguration);
164  }
165  }
166  }
167 } // namespace pinocchio
168 
169 #endif // ifndef __pinocchio_collision_parallel_geometry_hpp__
PINOCCHIO_CHECK_ARGUMENT_SIZE
#define PINOCCHIO_CHECK_ARGUMENT_SIZE(...)
Macro to check if the size of an element is equal to the expected size.
Definition: include/pinocchio/macros.hpp:217
pinocchio::DataTpl
Definition: context/generic.hpp:25
PINOCCHIO_CHECK_INPUT_ARGUMENT
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
Macro to check an assert-like condition and throw a std::invalid_argument exception (with a message) ...
Definition: include/pinocchio/macros.hpp:193
pinocchio::computeCollisions
bool computeCollisions(BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, CollisionCallBackBase *callback)
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeome...
Definition: broadphase.hpp:34
pinocchio::updateGeometryPlacements
void updateGeometryPlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::MatrixBase< ConfigVectorType > &q)
Apply a forward kinematics and update the placement of the geometry objects.
collision-with-point-clouds.collision_pair
collision_pair
Definition: collision-with-point-clouds.py:85
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
omp.hpp
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:20
run-algo-in-parallel.num_threads
num_threads
Definition: run-algo-in-parallel.py:10
setup.data
data
Definition: cmake/cython/setup.in.py:48
geometry.hpp
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::res
ReturnType res
Definition: spatial/classic-acceleration.hpp:57
pinocchio::GeometryData
Definition: multibody/geometry.hpp:233
run-algo-in-parallel.batch_size
int batch_size
Definition: run-algo-in-parallel.py:11
pinocchio::python::context::Model
ModelTpl< Scalar, Options > Model
Definition: bindings/python/context/generic.hpp:61
collision.hpp
geometry.hpp
pinocchio::CollisionPair
Definition: multibody/geometry.hpp:21
pinocchio::python::context::Data
DataTpl< Scalar, Options > Data
Definition: bindings/python/context/generic.hpp:62
pinocchio::Data
DataTpl< context::Scalar, context::Options > Data
Definition: multibody/fwd.hpp:34
run-algo-in-parallel.pool
pool
Definition: run-algo-in-parallel.py:8
pinocchio::computeCollision
bool computeCollision(const GeometryModel &geom_model, GeometryData &geom_data, const PairIndex pair_id, fcl::CollisionRequest &collision_request)
Compute the collision status between a SINGLE collision pair. The result is store in the collisionRes...
int64_t
int64_t
append-urdf-model-with-another-model.geom_model
geom_model
Definition: append-urdf-model-with-another-model.py:26
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
collisions.geom_data
geom_data
Definition: collisions.py:45
pinocchio::computeCollisionsInParallel
void computeCollisionsInParallel(const size_t num_threads, BroadPhaseManagerPoolBase< BroadPhaseManagerDerived, Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< CollisionVectorResult > &res, const bool stopAtFirstCollisionInConfiguration=false, const bool stopAtFirstCollisionInBatch=false)
Definition: parallel/broadphase.hpp:26
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
pinocchio::set_default_omp_options
void set_default_omp_options(const size_t num_threads=(size_t) omp_get_max_threads())
Definition: omp.hpp:12
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::ModelTpl::nq
int nq
Dimension of the configuration vector representation.
Definition: multibody/model.hpp:99
pinocchio::Model
ModelTpl< context::Scalar, context::Options > Model
Definition: multibody/fwd.hpp:33
pinocchio::GeometryPoolTpl
Definition: multibody/pool/fwd.hpp:24
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:47