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> class JointCollectionTpl,
66  typename ConfigVectorType>
68  const size_t num_threads,
71  const GeometryModel & geom_model,
73  const Eigen::MatrixBase<ConfigVectorType> & q,
74  const bool stopAtFirstCollision = false)
75  {
77  return computeCollisionsInParallel(num_threads, geom_model, geom_data, stopAtFirstCollision);
78  }
79 
80  template<
81  typename Scalar,
82  int Options,
83  template<typename, int> class JointCollectionTpl,
84  typename ConfigVectorPool,
85  typename CollisionVectorResult>
87  const size_t num_threads,
89  const Eigen::MatrixBase<ConfigVectorPool> & q,
90  const Eigen::MatrixBase<CollisionVectorResult> & res,
91  const bool stopAtFirstCollisionInConfiguration = false,
92  const bool stopAtFirstCollisionInBatch = false)
93  {
95  typedef typename Pool::Model Model;
96  typedef typename Pool::Data Data;
97  typedef typename Pool::GeometryModel GeometryModel;
98  typedef typename Pool::GeometryData GeometryData;
99  typedef typename Pool::ModelVector ModelVector;
100  typedef typename Pool::DataVector DataVector;
101  typedef typename Pool::GeometryModelVector GeometryModelVector;
102  typedef typename Pool::GeometryDataVector GeometryDataVector;
103 
104  PINOCCHIO_CHECK_INPUT_ARGUMENT(pool.size() > 0, "The pool should have at least one element");
105  PINOCCHIO_CHECK_INPUT_ARGUMENT(num_threads <= pool.size(), "The pool is too small");
106 
107  const ModelVector & models = pool.getModels();
108  const Model & model_check = models[0];
109  const GeometryModelVector & geometry_models = pool.getGeometryModels();
110  DataVector & datas = pool.getDatas();
111  GeometryDataVector & geometry_datas = pool.getGeometryDatas();
112  CollisionVectorResult & res_ = res.const_cast_derived();
113 
114  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.rows(), model_check.nq);
115  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), res.size());
116  res_.fill(false);
117 
119  const Eigen::DenseIndex batch_size = res.size();
120 
121  if (stopAtFirstCollisionInBatch)
122  {
123  bool is_colliding = false;
124  Eigen::DenseIndex i = 0;
125 #pragma omp parallel for schedule(static)
126  for (i = 0; i < batch_size; i++)
127  {
128  if (is_colliding)
129  continue;
130 
131  const int thread_id = omp_get_thread_num();
132 
133  const Model & model = models[(size_t)thread_id];
134  Data & data = datas[(size_t)thread_id];
135  const GeometryModel & geometry_model = geometry_models[(size_t)thread_id];
136  GeometryData & geometry_data = geometry_datas[(size_t)thread_id];
137  res_[i] = computeCollisions(
138  model, data, geometry_model, geometry_data, q.col(i),
139  stopAtFirstCollisionInConfiguration);
140 
141  if (res_[i])
142  {
143  is_colliding = true;
144  }
145  }
146  }
147  else
148  {
149  Eigen::DenseIndex i = 0;
150 #pragma omp parallel for schedule(static)
151  for (i = 0; i < batch_size; i++)
152  {
153  const int thread_id = omp_get_thread_num();
154 
155  const Model & model = models[(size_t)thread_id];
156  Data & data = datas[(size_t)thread_id];
157  const GeometryModel & geometry_model = geometry_models[(size_t)thread_id];
158  GeometryData & geometry_data = geometry_datas[(size_t)thread_id];
159  res_[i] = computeCollisions(
160  model, data, geometry_model, geometry_data, q.col(i),
161  stopAtFirstCollisionInConfiguration);
162  }
163  }
164  }
165 } // namespace pinocchio
166 
167 #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:216
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:192
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:87
pinocchio::Options
Options
Definition: joint-configuration.hpp:1082
omp.hpp
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:17
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:63
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:64
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:1083
collisions.geom_data
geom_data
Definition: collisions.py:42
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:25
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:98
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:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Mon Dec 16 2024 03:41:01