5 #ifndef __pinocchio_algorithm_parallel_geometry_hpp__ 6 #define __pinocchio_algorithm_parallel_geometry_hpp__ 10 #include "pinocchio/multibody/pool/geometry.hpp" 11 #include "pinocchio/algorithm/geometry.hpp" 19 const bool stopAtFirstCollision =
false)
21 bool is_colliding =
false;
23 omp_set_num_threads(num_threads);
24 std::size_t cp_index = 0;
26 #pragma omp parallel for 27 for(cp_index = 0; cp_index < geom_model.
collisionPairs.size(); ++cp_index)
29 if(stopAtFirstCollision && is_colliding)
continue;
36 fcl::CollisionRequest & collision_request = geom_data.collisionRequests[cp_index];
37 collision_request.distance_upper_bound = collision_request.security_margin + 1e-6;
39 fcl::CollisionResult & collision_result = geom_data.collisionResults[cp_index];
40 collision_result.clear();
45 const GeometryData::ComputeCollision & do_computations = geom_data.collision_functors[cp_index];
46 std::size_t
res = do_computations(oM1, oM2, collision_request, collision_result);
48 if(!is_colliding && res)
51 geom_data.collisionPairIndex = cp_index;
59 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
65 const Eigen::MatrixBase<ConfigVectorType> &
q,
66 const bool stopAtFirstCollision =
false)
69 return computeCollisions(num_threads, geom_model, geom_data, stopAtFirstCollision);
72 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorPool,
typename CollisionVectorResult>
75 const Eigen::MatrixBase<ConfigVectorPool> &
q,
76 const Eigen::MatrixBase<CollisionVectorResult> & res,
77 const bool stopAtFirstCollision =
false)
84 typedef typename Pool::DataVector DataVector;
85 typedef typename Pool::GeometryDataVector GeometryDataVector;
89 DataVector & datas = pool.
datas();
91 CollisionVectorResult & res_ = res.const_cast_derived();
98 omp_set_num_threads(num_threads);
99 const Eigen::DenseIndex
batch_size = res.size();
100 Eigen::DenseIndex
i = 0;
102 #pragma omp parallel for 105 const int thread_id = omp_get_thread_num();
106 Data &
data = datas[(size_t)thread_id];
107 GeometryData & geometry_data = geometry_datas[(size_t)thread_id];
108 res_[
i] =
computeCollisions(model,data,geometry_model,geometry_data,q.col(i),stopAtFirstCollision);
113 #endif // ifndef __pinocchio_algorithm_parallel_geometry_hpp__ const DataVector & datas() const
Returns the data vectors.
const GeometryDataVector & geometry_datas() const
Vector of Geometry Data.
CollisionPairVector collisionPairs
Vector of collision pairs.
std::vector< bool > activeCollisionPairs
Vector of collision pairs.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
bool computeCollisions(const int num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false)
int size() const
Returns the size of the pool.
GeometryObjectVector geometryObjects
Vector of GeometryObjects used for collision computations.
#define PINOCCHIO_CHECK_ARGUMENT_SIZE(...)
Macro to check if the size of an element is equal to the expected size.
const Model & model() const
Returns the model stored within the pool.
hpp::fcl::Transform3f toFclTransform3f(const SE3 &m)
Main pinocchio namespace.
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.
const GeometryModel & geometry_model() const
Returns the geometry model.
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
Macro to check an assert-like condition and throw a std::invalid_argument exception (with a message) ...
JointCollectionTpl & model
int nq
Dimension of the configuration vector representation.