bindings/python/collision/parallel/geometry.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021-2022 INRIA
3 //
4 
8 
10 
11 namespace pinocchio
12 {
13  namespace python
14  {
15 
16  using namespace Eigen;
17 
18  typedef Eigen::Matrix<bool, Eigen::Dynamic, 1> VectorXb;
19 
21  const size_t num_threads,
22  const GeometryModel & geom_model,
24  const bool stopAtFirstCollision = false)
25  {
26  return computeCollisionsInParallel(num_threads, geom_model, geom_data, stopAtFirstCollision);
27  }
28 
30  const size_t num_threads,
31  const Model & model,
32  Data & data,
33  const GeometryModel & geom_model,
35  const Eigen::VectorXd & q,
36  const bool stopAtFirstCollision = false)
37  {
39  num_threads, model, data, geom_model, geom_data, q, stopAtFirstCollision);
40  }
41 
43  const int num_thread,
45  const Eigen::MatrixXd & q,
46  bool stopAtFirstCollisionInConfiguration = false,
47  bool stopAtFirstCollisionInBatch = false)
48  {
49  VectorXb res(q.cols());
51  num_thread, pool, q, res, stopAtFirstCollisionInConfiguration, stopAtFirstCollisionInBatch);
52  return res;
53  }
54 
56  {
57  namespace bp = boost::python;
58 
59  using namespace Eigen;
60 
61  bp::def(
62  "computeCollisionsInParallel", computeCollisionsInParallel_proxy,
63  (bp::arg("num_thread"), bp::arg("geometry_model"), bp::arg("geometry_data"),
64  bp::arg("stop_at_first_collision") = false),
65  "Evaluates in parallel the collisions for a single data and returns the result.\n\n"
66  "Parameters:\n"
67  "\tnum_thread: number of threads used for the computation\n"
68  "\tgeometry_model: the geometry model\n"
69  "\tgeometry_data: the geometry data\n"
70  "\tstop_at_first_collision: if set to true, stops when encountering the first "
71  "collision.\n");
72 
73  bp::def(
74  "computeCollisionsInParallel", computeCollisionsInParallel_full_proxy,
75  (bp::arg("num_thread"), bp::arg("model"), bp::arg("data"), bp::arg("geometry_model"),
76  bp::arg("geometry_data"), bp::arg("q"), bp::arg("stop_at_first_collision") = false),
77  "Evaluates in parallel the collisions for a single data and returns the result.\n\n"
78  "Parameters:\n"
79  "\tnum_thread: number of threads used for the computation\n"
80  "\tmodel: the kinematic model\n"
81  "\tdata: the data associated to the model\n"
82  "\tgeometry_model: the geometry model\n"
83  "\tgeometry_data: the geometry data associated to the tgeometry_model\n"
84  "\tq: the joint configuration vector (size model.nq)\n"
85  "\tstop_at_first_collision: if set to true, stops when encountering the first "
86  "collision.\n");
87 
88  bp::def(
89  "computeCollisionsInParallel", computeCollisionsInParallel_pool_proxy,
90  (bp::arg("num_thread"), bp::arg("pool"), bp::arg("q"),
91  bp::arg("stop_at_first_collision_in_configuration") = false,
92  bp::arg("stop_at_first_collision_in_batch") = false),
93  "Evaluates in parallel the collisions and returns the result.\n\n"
94  "Parameters:\n"
95  "\tnum_thread: number of threads used for the computation\n"
96  "\tpool: pool of geometry model/ geometry data\n"
97  "\tq: the joint configuration vector (size model.nq x batch_size)\n"
98  "\tstop_at_first_collision_in_configuration: if set to true, stops when encountering "
99  "the first collision in a configuration\n"
100  "\tstop_at_first_collision_in_batch: if set to true, stops when encountering the "
101  "first collision in a batch.\n");
102  }
103 
104  } // namespace python
105 } // namespace pinocchio
boost::python
Eigen
pinocchio::DataTpl
Definition: context/generic.hpp:25
eigen-from-python.hpp
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
pinocchio::GeometryData
Definition: multibody/geometry.hpp:233
pinocchio::python::computeCollisionsInParallel_full_proxy
static bool computeCollisionsInParallel_full_proxy(const size_t num_threads, const Model &model, Data &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::VectorXd &q, const bool stopAtFirstCollision=false)
Definition: bindings/python/collision/parallel/geometry.cpp:29
algorithms.hpp
python
run-algo-in-parallel.pool
pool
Definition: run-algo-in-parallel.py:8
pinocchio::python::computeCollisionsInParallel_proxy
static bool computeCollisionsInParallel_proxy(const size_t num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false)
Definition: bindings/python/collision/parallel/geometry.cpp:20
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
pinocchio::python::computeCollisionsInParallel_pool_proxy
static VectorXb computeCollisionsInParallel_pool_proxy(const int num_thread, GeometryPool &pool, const Eigen::MatrixXd &q, bool stopAtFirstCollisionInConfiguration=false, bool stopAtFirstCollisionInBatch=false)
Definition: bindings/python/collision/parallel/geometry.cpp:42
collisions.geom_data
geom_data
Definition: collisions.py:45
geometry.hpp
pinocchio::python::VectorXb
Eigen::Matrix< bool, Eigen::Dynamic, 1 > VectorXb
Definition: bindings/python/collision/parallel/broadphase.cpp:28
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::python::exposeParallelGeometry
void exposeParallelGeometry()
Definition: bindings/python/collision/parallel/geometry.cpp:55
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::python::res
ReturnType res
Definition: bindings/python/spatial/explog.hpp:68
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
broadphase.hpp


pinocchio
Author(s):
autogenerated on Wed Jun 19 2024 02:41:13