Template Struct BroadPhaseManagerTpl
Defined in File broadphase-manager.hpp
Inheritance Relationships
Base Type
public pinocchio::BroadPhaseManagerBase< BroadPhaseManagerTpl< _Manager > >
(Template Struct BroadPhaseManagerBase)
Struct Documentation
-
template<typename _Manager>
struct BroadPhaseManagerTpl : public pinocchio::BroadPhaseManagerBase<BroadPhaseManagerTpl<_Manager>> Public Types
-
typedef std::vector<CollisionObject> CollisionObjectVector
-
typedef Eigen::VectorXd VectorXs
-
typedef ::pinocchio::Model Model
-
typedef ::pinocchio::GeometryModel GeometryModel
-
typedef ::pinocchio::GeometryData GeometryData
Public Functions
-
inline BroadPhaseManagerTpl()
Default constructor.
-
inline BroadPhaseManagerTpl(const Model *model_ptr, const GeometryModel *geometry_model_ptr, GeometryData *geometry_data_ptr, const GeometryObjectFilterBase &filter = GeometryObjectFilterNothing())
Constructor from a given geometry model and data.
- Parameters:
model_ptr – [in] pointer to the model.
geometry_model_ptr – [in] pointer to the geometry model.
geometry_data_ptr – [in] pointer to the geometry data.
-
inline BroadPhaseManagerTpl(const BroadPhaseManagerTpl &other)
Copy contructor.
- Parameters:
other – [in] manager to copy.
-
void update(bool compute_local_aabb = false)
Update the manager from the current geometry positions and update the underlying FCL broad phase manager.
- Parameters:
compute_local_aabb – [in] whether to recompute the local AABB of the collision geometries which have changed.
-
void update(GeometryData *geom_data_ptr_new)
Update the manager with a new geometry data.
- Parameters:
geom_data_ptr_new – [in] pointer to the new geometry data.
-
~BroadPhaseManagerTpl()
-
bool check() const
Check whether the base broad phase manager is aligned with the current collision_objects.
-
bool check(CollisionCallBackBase *callback) const
Check whether the callback is inline with *this.
-
inline const CollisionObjectVector &getCollisionObjects() const
Returns the vector of collision objects associated to the manager.
-
inline CollisionObjectVector &getCollisionObjects()
Returns the vector of collision objects associated to the manager.
-
inline const VectorXs &getCollisionObjectInflation()
Returns the inflation value related to each collision object.
-
bool collide(CollisionObject &obj, CollisionCallBackBase *callback) const
Performs collision test between one object and all the objects belonging to the manager.
-
bool collide(CollisionCallBackBase *callback) const
Performs collision test for the objects belonging to the manager.
-
bool collide(BroadPhaseManagerTpl &other_manager, CollisionCallBackBase *callback) const
Performs collision test with objects belonging to another manager.
-
inline const std::vector<bool> &getCollisionObjectStatus() const
Returns the status of the collision object.
Public Members
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef BroadPhaseManagerBase< BroadPhaseManagerTpl< _Manager > > Base
Protected Functions
-
void init()
Initialialisation of BroadPhaseManagerTpl.
Protected Attributes
-
CollisionObjectVector collision_objects
the vector of collision objects.
-
std::vector<size_t> selected_geometry_objects
Selected geometry objects in the original geometry_model.
-
std::vector<size_t> geometry_to_collision_index
Mapping between a given geometry index and a collision index.
-
std::vector<size_t> selected_collision_pairs
Selected collision pairs in the original geometry_model.
-
std::vector<bool> collision_object_is_active
Disable status related to each collision objects.
-
typedef std::vector<CollisionObject> CollisionObjectVector