Go to the documentation of this file.
5 #ifndef __pinocchio_collision_broadphase_hpp__
6 #define __pinocchio_collision_broadphase_hpp__
33 template<
typename BroadPhaseManagerDerived>
56 template<
typename BroadPhaseManagerDerived>
59 const bool stopAtFirstCollision =
false)
63 stopAtFirstCollision);
91 template<
typename,
int>
class JointCollectionTpl,
92 typename BroadPhaseManagerDerived,
93 typename ConfigVectorType>
99 const Eigen::MatrixBase<ConfigVectorType> &
q)
104 broadphase_manager.
update(
false);
130 template<
typename,
int>
class JointCollectionTpl,
131 typename BroadPhaseManagerDerived,
132 typename ConfigVectorType>
137 const Eigen::MatrixBase<ConfigVectorType> &
q,
138 const bool stopAtFirstCollision =
false)
143 broadphase_manager.
update(
false);
147 stopAtFirstCollision);
154 #include "pinocchio/collision/broadphase.hxx"
156 #endif // ifndef __pinocchio_collision_broadphase_hpp__
bool collide(CollisionObject &obj, CollisionCallBackBase *callback) const
Performs collision test between one object and all the objects belonging to the manager.
const GeometryModel & getGeometryModel() const
Returns the geometry model associated to the manager.
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
Macro to check an assert-like condition and throw a std::invalid_argument exception (with a message) ...
bool computeCollisions(BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, CollisionCallBackBase *callback)
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeome...
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 GeometryData & getGeometryData() const
Returns the geometry data associated to the manager.
Interface for Pinocchio collision callback functors.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
void update(bool compute_local_aabb=false)
Update the manager from the current geometry positions and update the underlying FCL broad phase mana...
bool check() const
Check whether the base broad phase manager is aligned with the current collision_objects.
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:39