GCC Code Coverage Report


Directory: ./
File: include/pinocchio/collision/broadphase.hpp
Date: 2024-08-27 18:20:05
Exec Total Coverage
Lines: 0 17 0.0%
Branches: 0 12 0.0%

Line Branch Exec Source
1 //
2 // Copyright (c) 2022 INRIA
3 //
4
5 #ifndef __pinocchio_collision_broadphase_hpp__
6 #define __pinocchio_collision_broadphase_hpp__
7
8 #include <hpp/fcl/broadphase/broadphase_collision_manager.h>
9
10 #include "pinocchio/multibody/fcl.hpp"
11
12 #include "pinocchio/algorithm/geometry.hpp"
13
14 #include "pinocchio/collision/broadphase-manager.hpp"
15 #include "pinocchio/collision/broadphase-callbacks.hpp"
16
17 namespace pinocchio
18 {
19
20 ///
21 /// \brief Calls computeCollision for every active pairs of GeometryData.
22 /// This function assumes that \ref updateGeometryPlacements and broadphase_manager.update() have
23 /// been called first.
24 ///
25 /// \param[in] broadphase_manager broadphase instance for collision detection.
26 /// \param[in] callback callback pointer used for collision detection.
27 /// \param[in] stopAtFirstCollision if true, stop the loop over the collision pairs when the first
28 /// collision is detected.
29 ///
30 /// \warning if stopAtFirstcollision = true, then the collisions vector will
31 /// not be entirely fulfilled (of course).
32 ///
33 template<typename BroadPhaseManagerDerived>
34 bool computeCollisions(
35 BroadPhaseManagerBase<BroadPhaseManagerDerived> & broadphase_manager,
36 CollisionCallBackBase * callback)
37 {
38 PINOCCHIO_CHECK_INPUT_ARGUMENT(broadphase_manager.check(callback));
39 broadphase_manager.collide(callback);
40 callback->done();
41 return callback->collision;
42 }
43
44 ///
45 /// \brief Calls computeCollision for every active pairs of GeometryData.
46 /// This function assumes that \ref updateGeometryPlacements and broadphase_manager.update() have
47 /// been called first.
48 ///
49 /// \param[in] broadphase_manager broadphase instance for collision detection.
50 /// \param[in] stopAtFirstCollision if true, stop the loop over the collision pairs when the first
51 /// collision is detected.
52 ///
53 /// \warning if stopAtFirstcollision = true, then the collisions vector will
54 /// not be entirely fulfilled (of course).
55 ///
56 template<typename BroadPhaseManagerDerived>
57 bool computeCollisions(
58 BroadPhaseManagerBase<BroadPhaseManagerDerived> & broadphase_manager,
59 const bool stopAtFirstCollision = false)
60 {
61 CollisionCallBackDefault callback(
62 broadphase_manager.getGeometryModel(), broadphase_manager.getGeometryData(),
63 stopAtFirstCollision);
64
65 return computeCollisions(broadphase_manager, &callback);
66 }
67
68 ///
69 /// Compute the forward kinematics, update the geometry placements and run the collision detection
70 /// using the broadphase manager.
71 ///
72 /// \tparam JointCollection Collection of Joint types.
73 /// \tparam ConfigVectorType Type of the joint configuration vector.
74 ///
75 /// \param[in] model robot model (const)
76 /// \param[out] data corresponding data (nonconst) where the forward kinematics results are stored
77 /// \param[in] broadphase_manager broadphase manager for collision detection.
78 /// \param[in] callback callback pointer used for collision detection.///
79 /// \param[in] q robot configuration.
80 /// \param[in] stopAtFirstCollision if true, stop the loop over the collision pairs when the first
81 /// collision is detected.
82 ///
83 /// \warning if stopAtFirstcollision = true, then the collisions vector will
84 /// not be entirely fulfilled (of course).
85 /// \note A similar function is available without model, data and q, not recomputing the forward
86 /// kinematics.
87 ///
88 template<
89 typename Scalar,
90 int Options,
91 template<typename, int>
92 class JointCollectionTpl,
93 typename BroadPhaseManagerDerived,
94 typename ConfigVectorType>
95 inline bool computeCollisions(
96 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
97 DataTpl<Scalar, Options, JointCollectionTpl> & data,
98 BroadPhaseManagerBase<BroadPhaseManagerDerived> & broadphase_manager,
99 CollisionCallBackBase * callback,
100 const Eigen::MatrixBase<ConfigVectorType> & q)
101 {
102 updateGeometryPlacements(
103 model, data, broadphase_manager.getGeometryModel(), broadphase_manager.getGeometryData(), q);
104
105 broadphase_manager.update(false);
106 return computeCollisions(broadphase_manager, &callback);
107 }
108
109 ///
110 /// Compute the forward kinematics, update the geometry placements and run the collision detection
111 /// using the broadphase manager.
112 ///
113 /// \tparam JointCollection Collection of Joint types.
114 /// \tparam ConfigVectorType Type of the joint configuration vector.
115 ///
116 /// \param[in] model robot model (const)
117 /// \param[out] data corresponding data (nonconst) where the forward kinematics results are stored
118 /// \param[in] broadphase_manager broadphase manager for collision detection.
119 /// \param[in] q robot configuration.
120 /// \param[in] stopAtFirstCollision if true, stop the loop over the collision pairs when the first
121 /// collision is detected.
122 ///
123 /// \warning if stopAtFirstcollision = true, then the collisions vector will
124 /// not be entirely fulfilled (of course).
125 /// \note A similar function is available without model, data and q, not recomputing the forward
126 /// kinematics.
127 ///
128 template<
129 typename Scalar,
130 int Options,
131 template<typename, int>
132 class JointCollectionTpl,
133 typename BroadPhaseManagerDerived,
134 typename ConfigVectorType>
135 inline bool computeCollisions(
136 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
137 DataTpl<Scalar, Options, JointCollectionTpl> & data,
138 BroadPhaseManagerBase<BroadPhaseManagerDerived> & broadphase_manager,
139 const Eigen::MatrixBase<ConfigVectorType> & q,
140 const bool stopAtFirstCollision = false)
141 {
142 updateGeometryPlacements(
143 model, data, broadphase_manager.getGeometryModel(), broadphase_manager.getGeometryData(), q);
144
145 broadphase_manager.update(false);
146
147 CollisionCallBackDefault callback(
148 broadphase_manager.getGeometryModel(), broadphase_manager.getGeometryData(),
149 stopAtFirstCollision);
150 return computeCollisions(broadphase_manager, &callback);
151 }
152
153 } // namespace pinocchio
154
155 /* --- Details -------------------------------------------------------------------- */
156 #include "pinocchio/collision/broadphase.hxx"
157
158 #endif // ifndef __pinocchio_collision_broadphase_hpp__
159