#include <broadphase-manager.hpp>
Public Types | |
typedef std::vector< CollisionObject > | CollisionObjectVector |
typedef ::pinocchio::GeometryData | GeometryData |
typedef ::pinocchio::GeometryModel | GeometryModel |
typedef _Manager | Manager |
typedef ::pinocchio::Model | Model |
typedef Eigen::VectorXd | VectorXs |
Public Member Functions | |
BroadPhaseManagerTpl () | |
Default constructor. More... | |
BroadPhaseManagerTpl (const BroadPhaseManagerTpl &other) | |
Copy contructor. More... | |
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. More... | |
bool | check () const |
Check whether the base broad phase manager is aligned with the current collision_objects. More... | |
bool | check (CollisionCallBackBase *callback) const |
Check whether the callback is inline with *this. More... | |
bool | collide (BroadPhaseManagerTpl &other_manager, CollisionCallBackBase *callback) const |
Performs collision test with objects belonging to another manager. More... | |
bool | collide (CollisionCallBackBase *callback) const |
Performs collision test for the objects belonging to the manager. More... | |
bool | collide (CollisionObject &obj, CollisionCallBackBase *callback) const |
Performs collision test between one object and all the objects belonging to the manager. More... | |
const VectorXs & | getCollisionObjectInflation () |
Returns the inflation value related to each collision object. More... | |
CollisionObjectVector & | getCollisionObjects () |
Returns the vector of collision objects associated to the manager. More... | |
const CollisionObjectVector & | getCollisionObjects () const |
Returns the vector of collision objects associated to the manager. More... | |
const std::vector< bool > & | getCollisionObjectStatus () const |
Returns the status of the collision object. More... | |
Manager & | getManager () |
Returns internal manager. More... | |
const Manager & | getManager () const |
Returns internal manager. More... | |
void | update (bool compute_local_aabb=false) |
Update the manager from the current geometry positions and update the underlying FCL broad phase manager. More... | |
void | update (GeometryData *geom_data_ptr_new) |
Update the manager with a new geometry data. More... | |
~BroadPhaseManagerTpl () | |
Public Member Functions inherited from pinocchio::BroadPhaseManagerBase< BroadPhaseManagerTpl< _Manager > > | |
BroadPhaseManagerBase () | |
Default constructor. More... | |
BroadPhaseManagerBase (const BroadPhaseManagerBase &other) | |
Copy constructor. More... | |
BroadPhaseManagerBase (const Model *model_ptr, const GeometryModel *geometry_model_ptr, GeometryData *geometry_data_ptr) | |
Constructor from a given geometry model and geometry data. More... | |
bool | check () const |
Check whether the base broad phase manager is aligned with the current collision_objects. More... | |
bool | check (CollisionCallBackBase *callback) const |
Check whether the callback is inline with *this. More... | |
bool | collide (BroadPhaseManagerBase &other_manager, CollisionCallBackBase *callback) const |
Performs collision test with objects belonging to another manager. More... | |
bool | collide (CollisionCallBackBase *callback) const |
Performs collision test for the objects belonging to the manager. More... | |
bool | collide (CollisionObject &obj, CollisionCallBackBase *callback) const |
Performs collision test between one object and all the objects belonging to the manager. More... | |
BroadPhaseManagerTpl< _Manager > & | derived () |
const BroadPhaseManagerTpl< _Manager > & | derived () const |
GeometryData & | getGeometryData () |
Returns the geometry data associated to the manager. More... | |
const GeometryData & | getGeometryData () const |
Returns the geometry data associated to the manager. More... | |
const GeometryModel & | getGeometryModel () const |
Returns the geometry model associated to the manager. More... | |
const Model & | getModel () const |
Returns the model associated to the manager. More... | |
BroadPhaseManagerBase & | operator= (const BroadPhaseManagerBase &other) |
void | update (bool compute_local_aabb=false) |
Update the manager from the current geometry positions and update the underlying FCL broad phase manager. More... | |
void | update (GeometryData *geom_data_ptr_new) |
Update the manager with a new geometry data. More... | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef BroadPhaseManagerBase< BroadPhaseManagerTpl< _Manager > > | Base |
Protected Member Functions | |
void | init () |
Initialialisation of BroadPhaseManagerTpl. More... | |
Protected Attributes | |
VectorXs | collision_object_inflation |
the inflation value related to each collision object. More... | |
std::vector< bool > | collision_object_is_active |
Disable status related to each collision objects. More... | |
CollisionObjectVector | collision_objects |
the vector of collision objects. More... | |
std::vector< size_t > | geometry_to_collision_index |
Mapping between a given geometry index and a collision index. More... | |
Manager | manager |
internal manager More... | |
std::vector< size_t > | selected_collision_pairs |
Selected collision pairs in the original geometry_model. More... | |
std::vector< size_t > | selected_geometry_objects |
Selected geometry objects in the original geometry_model. More... | |
Protected Attributes inherited from pinocchio::BroadPhaseManagerBase< BroadPhaseManagerTpl< _Manager > > | |
GeometryData * | geometry_data_ptr |
Pointer to the geometry data. More... | |
const GeometryModel * | geometry_model_ptr |
Pointer to the geometry model. More... | |
const Model * | model_ptr |
Pointer to the model. More... | |
Definition at line 17 of file collision/broadphase-manager.hpp.
typedef std::vector<CollisionObject> pinocchio::BroadPhaseManagerTpl< _Manager >::CollisionObjectVector |
Definition at line 22 of file collision/broadphase-manager.hpp.
typedef ::pinocchio::GeometryData pinocchio::BroadPhaseManagerTpl< _Manager >::GeometryData |
Definition at line 28 of file collision/broadphase-manager.hpp.
typedef ::pinocchio::GeometryModel pinocchio::BroadPhaseManagerTpl< _Manager >::GeometryModel |
Definition at line 27 of file collision/broadphase-manager.hpp.
typedef _Manager pinocchio::BroadPhaseManagerTpl< _Manager >::Manager |
Definition at line 24 of file collision/broadphase-manager.hpp.
typedef ::pinocchio::Model pinocchio::BroadPhaseManagerTpl< _Manager >::Model |
Definition at line 26 of file collision/broadphase-manager.hpp.
typedef Eigen::VectorXd pinocchio::BroadPhaseManagerTpl< _Manager >::VectorXs |
Definition at line 23 of file collision/broadphase-manager.hpp.
|
inline |
Default constructor.
Definition at line 31 of file collision/broadphase-manager.hpp.
|
inline |
Constructor from a given geometry model and data.
[in] | model_ptr | pointer to the model. |
[in] | geometry_model_ptr | pointer to the geometry model. |
[in] | geometry_data_ptr | pointer to the geometry data. |
Definition at line 42 of file collision/broadphase-manager.hpp.
|
inline |
Copy contructor.
[in] | other | manager to copy. |
Definition at line 86 of file collision/broadphase-manager.hpp.
pinocchio::BroadPhaseManagerTpl< _Manager >::~BroadPhaseManagerTpl | ( | ) |
bool pinocchio::BroadPhaseManagerTpl< _Manager >::check | ( | ) | const |
Check whether the base broad phase manager is aligned with the current collision_objects.
bool pinocchio::BroadPhaseManagerTpl< _Manager >::check | ( | CollisionCallBackBase * | callback | ) | const |
Check whether the callback is inline with *this.
bool pinocchio::BroadPhaseManagerTpl< _Manager >::collide | ( | BroadPhaseManagerTpl< _Manager > & | other_manager, |
CollisionCallBackBase * | callback | ||
) | const |
Performs collision test with objects belonging to another manager.
bool pinocchio::BroadPhaseManagerTpl< _Manager >::collide | ( | CollisionCallBackBase * | callback | ) | const |
Performs collision test for the objects belonging to the manager.
bool pinocchio::BroadPhaseManagerTpl< _Manager >::collide | ( | CollisionObject & | obj, |
CollisionCallBackBase * | callback | ||
) | const |
Performs collision test between one object and all the objects belonging to the manager.
|
inline |
Returns the inflation value related to each collision object.
Definition at line 138 of file collision/broadphase-manager.hpp.
|
inline |
Returns the vector of collision objects associated to the manager.
Definition at line 132 of file collision/broadphase-manager.hpp.
|
inline |
Returns the vector of collision objects associated to the manager.
Definition at line 127 of file collision/broadphase-manager.hpp.
|
inline |
Returns the status of the collision object.
Definition at line 176 of file collision/broadphase-manager.hpp.
|
inline |
Returns internal manager.
Definition at line 164 of file collision/broadphase-manager.hpp.
|
inline |
Returns internal manager.
Definition at line 170 of file collision/broadphase-manager.hpp.
|
protected |
Initialialisation of BroadPhaseManagerTpl.
void pinocchio::BroadPhaseManagerTpl< _Manager >::update | ( | bool | compute_local_aabb = false | ) |
Update the manager from the current geometry positions and update the underlying FCL broad phase manager.
[in] | compute_local_aabb | whether to recompute the local AABB of the collision geometries which have changed. |
void pinocchio::BroadPhaseManagerTpl< _Manager >::update | ( | GeometryData * | geom_data_ptr_new | ) |
Update the manager with a new geometry data.
[in] | geom_data_ptr_new | pointer to the new geometry data. |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef BroadPhaseManagerBase<BroadPhaseManagerTpl<_Manager> > pinocchio::BroadPhaseManagerTpl< _Manager >::Base |
Definition at line 21 of file collision/broadphase-manager.hpp.
|
protected |
the inflation value related to each collision object.
Definition at line 189 of file collision/broadphase-manager.hpp.
|
protected |
Disable status related to each collision objects.
Definition at line 201 of file collision/broadphase-manager.hpp.
|
protected |
the vector of collision objects.
Definition at line 186 of file collision/broadphase-manager.hpp.
|
protected |
Mapping between a given geometry index and a collision index.
Definition at line 195 of file collision/broadphase-manager.hpp.
|
protected |
internal manager
Definition at line 183 of file collision/broadphase-manager.hpp.
|
protected |
Selected collision pairs in the original geometry_model.
Definition at line 198 of file collision/broadphase-manager.hpp.
|
protected |
Selected geometry objects in the original geometry_model.
Definition at line 192 of file collision/broadphase-manager.hpp.