collision/collision.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_collision_collision_hpp__
6 #define __pinocchio_collision_collision_hpp__
7 
11 
12 #include "pinocchio/collision/config.hpp"
13 
14 #include <hpp/fcl/collision_data.h>
15 
16 namespace pinocchio
17 {
18 
31  bool computeCollision(
32  const GeometryModel & geom_model,
33  GeometryData & geom_data,
34  const PairIndex pair_id,
35  fcl::CollisionRequest & collision_request);
36 
48  bool computeCollision(
49  const GeometryModel & geom_model, GeometryData & geom_data, const PairIndex pair_id);
50 
63  bool computeCollisions(
64  const GeometryModel & geom_model,
65  GeometryData & geom_data,
66  const bool stopAtFirstCollision = false);
67 
88  template<
89  typename Scalar,
90  int Options,
91  template<typename, int> class JointCollectionTpl,
92  typename ConfigVectorType>
93  bool computeCollisions(
94  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
95  DataTpl<Scalar, Options, JointCollectionTpl> & data,
96  const GeometryModel & geom_model,
97  GeometryData & geom_data,
98  const Eigen::MatrixBase<ConfigVectorType> & q,
99  const bool stopAtFirstCollision = false);
100 
110  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
111  void computeBodyRadius(
112  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
113  const GeometryModel & geom_model,
114  GeometryData & geom_data);
115 
116 } // namespace pinocchio
117 
118 /* --- Details -------------------------------------------------------------------- */
119 #include "pinocchio/collision/collision.hxx"
120 
121 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
122  #include "pinocchio/collision/collision.txx"
123 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
124 
125 #endif // ifndef __pinocchio_collision_collision_hpp__
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::Options
Options
Definition: joint-configuration.hpp:1082
model.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
collision_data.h
data.hpp
pinocchio::PairIndex
Index PairIndex
Definition: multibody/fwd.hpp:29
geometry.hpp
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...
append-urdf-model-with-another-model.geom_model
geom_model
Definition: append-urdf-model-with-another-model.py:25
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1083
collisions.geom_data
geom_data
Definition: collisions.py:42
pinocchio::computeBodyRadius
void computeBodyRadius(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const GeometryModel &geom_model, GeometryData &geom_data)
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sun Nov 10 2024 03:42:55