Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
pinocchio::TreeBroadPhaseManagerTpl< _Manager > Struct Template Reference

#include <fwd.hpp>

Public Types

typedef BroadPhaseManagerBase< TreeBroadPhaseManagerTpl< _Manager > > Base
 
typedef BroadPhaseManagerTpl< ManagerBroadPhaseManager
 
typedef std::vector< BroadPhaseManagerBroadPhaseManagerVector
 
typedef std::vector< hpp::fcl::CollisionObject * > CollisionObjectPointerVector
 
typedef BroadPhaseManager::GeometryData GeometryData
 
typedef BroadPhaseManager::GeometryModel GeometryModel
 
typedef BroadPhaseManager::Model Model
 

Public Member Functions

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 (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...
 
bool collide (TreeBroadPhaseManagerTpl &other_manager, CollisionCallBackBase *callback) const
 Performs collision test with objects belonging to another manager. More...
 
BroadPhaseManagerVectorgetBroadPhaseManagers ()
 Returns internal broad phase managers. More...
 
const BroadPhaseManagerVectorgetBroadPhaseManagers () const
 Returns internal broad phase managers. More...
 
GeometryDatagetGeometryData ()
 Returns the geometry data associated to the manager. More...
 
const GeometryDatagetGeometryData () const
 Returns the geometry data associated to the manager. More...
 
const GeometryModelgetGeometryModel () const
 Returns the geometry model associated to the manager. More...
 
const ModelgetModel () const
 Returns the model associated to the manager. More...
 
 TreeBroadPhaseManagerTpl ()
 Default constructor. More...
 
 TreeBroadPhaseManagerTpl (const Model *model_ptr, const GeometryModel *geometry_model_ptr, GeometryData *geometry_data_ptr)
 Constructor from a given geometry model and data. More...
 
 TreeBroadPhaseManagerTpl (const TreeBroadPhaseManagerTpl &other)
 Copy contructor. 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...
 
 ~TreeBroadPhaseManagerTpl ()
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Manager Manager
 

Protected Member Functions

void init (const size_t njoints)
 Initialialisation. More...
 

Protected Attributes

BroadPhaseManagerVector managers
 the vector of collision objects. More...
 

Detailed Description

template<typename _Manager>
struct pinocchio::TreeBroadPhaseManagerTpl< _Manager >

Definition at line 38 of file collision/pool/fwd.hpp.

Member Typedef Documentation

◆ Base

template<typename _Manager >
typedef BroadPhaseManagerBase<TreeBroadPhaseManagerTpl<_Manager> > pinocchio::TreeBroadPhaseManagerTpl< _Manager >::Base

Definition at line 19 of file collision/tree-broadphase-manager.hpp.

◆ BroadPhaseManager

template<typename _Manager >
typedef BroadPhaseManagerTpl<Manager> pinocchio::TreeBroadPhaseManagerTpl< _Manager >::BroadPhaseManager

Definition at line 20 of file collision/tree-broadphase-manager.hpp.

◆ BroadPhaseManagerVector

template<typename _Manager >
typedef std::vector<BroadPhaseManager> pinocchio::TreeBroadPhaseManagerTpl< _Manager >::BroadPhaseManagerVector

Definition at line 23 of file collision/tree-broadphase-manager.hpp.

◆ CollisionObjectPointerVector

template<typename _Manager >
typedef std::vector<hpp::fcl::CollisionObject *> pinocchio::TreeBroadPhaseManagerTpl< _Manager >::CollisionObjectPointerVector

Definition at line 22 of file collision/tree-broadphase-manager.hpp.

◆ GeometryData

template<typename _Manager >
typedef BroadPhaseManager::GeometryData pinocchio::TreeBroadPhaseManagerTpl< _Manager >::GeometryData

Definition at line 27 of file collision/tree-broadphase-manager.hpp.

◆ GeometryModel

template<typename _Manager >
typedef BroadPhaseManager::GeometryModel pinocchio::TreeBroadPhaseManagerTpl< _Manager >::GeometryModel

Definition at line 26 of file collision/tree-broadphase-manager.hpp.

◆ Model

template<typename _Manager >
typedef BroadPhaseManager::Model pinocchio::TreeBroadPhaseManagerTpl< _Manager >::Model

Definition at line 25 of file collision/tree-broadphase-manager.hpp.

Constructor & Destructor Documentation

◆ TreeBroadPhaseManagerTpl() [1/3]

template<typename _Manager >
pinocchio::TreeBroadPhaseManagerTpl< _Manager >::TreeBroadPhaseManagerTpl ( )
inline

Default constructor.

Definition at line 30 of file collision/tree-broadphase-manager.hpp.

◆ TreeBroadPhaseManagerTpl() [2/3]

template<typename _Manager >
pinocchio::TreeBroadPhaseManagerTpl< _Manager >::TreeBroadPhaseManagerTpl ( const Model model_ptr,
const GeometryModel geometry_model_ptr,
GeometryData geometry_data_ptr 
)
inline

Constructor from a given geometry model and data.

Parameters
[in]model_ptrpointer to the model of the kinematic tree.
[in]geometry_model_ptrpointer to the geometry model.
[in]geometry_data_ptrpointer to the geometry data.

Definition at line 41 of file collision/tree-broadphase-manager.hpp.

◆ TreeBroadPhaseManagerTpl() [3/3]

template<typename _Manager >
pinocchio::TreeBroadPhaseManagerTpl< _Manager >::TreeBroadPhaseManagerTpl ( const TreeBroadPhaseManagerTpl< _Manager > &  other)
inline

Copy contructor.

Parameters
[in]othermanager to copy.

Definition at line 54 of file collision/tree-broadphase-manager.hpp.

◆ ~TreeBroadPhaseManagerTpl()

template<typename _Manager >
pinocchio::TreeBroadPhaseManagerTpl< _Manager >::~TreeBroadPhaseManagerTpl ( )
inline

Definition at line 80 of file collision/tree-broadphase-manager.hpp.

Member Function Documentation

◆ check() [1/2]

template<typename _Manager >
bool pinocchio::TreeBroadPhaseManagerTpl< _Manager >::check ( ) const

Check whether the base broad phase manager is aligned with the current collision_objects.

◆ check() [2/2]

template<typename _Manager >
bool pinocchio::TreeBroadPhaseManagerTpl< _Manager >::check ( CollisionCallBackBase callback) const

Check whether the callback is inline with *this.

◆ collide() [1/3]

template<typename _Manager >
bool pinocchio::TreeBroadPhaseManagerTpl< _Manager >::collide ( CollisionCallBackBase callback) const

Performs collision test for the objects belonging to the manager.

◆ collide() [2/3]

template<typename _Manager >
bool pinocchio::TreeBroadPhaseManagerTpl< _Manager >::collide ( CollisionObject obj,
CollisionCallBackBase callback 
) const

Performs collision test between one object and all the objects belonging to the manager.

◆ collide() [3/3]

template<typename _Manager >
bool pinocchio::TreeBroadPhaseManagerTpl< _Manager >::collide ( TreeBroadPhaseManagerTpl< _Manager > &  other_manager,
CollisionCallBackBase callback 
) const

Performs collision test with objects belonging to another manager.

◆ getBroadPhaseManagers() [1/2]

template<typename _Manager >
BroadPhaseManagerVector& pinocchio::TreeBroadPhaseManagerTpl< _Manager >::getBroadPhaseManagers ( )
inline

Returns internal broad phase managers.

Definition at line 118 of file collision/tree-broadphase-manager.hpp.

◆ getBroadPhaseManagers() [2/2]

template<typename _Manager >
const BroadPhaseManagerVector& pinocchio::TreeBroadPhaseManagerTpl< _Manager >::getBroadPhaseManagers ( ) const
inline

Returns internal broad phase managers.

Definition at line 112 of file collision/tree-broadphase-manager.hpp.

◆ getGeometryData() [1/2]

template<typename _Manager >
GeometryData& pinocchio::BroadPhaseManagerBase< Derived >::getGeometryData
inline

Returns the geometry data associated to the manager.

Definition at line 145 of file collision/broadphase-manager-base.hpp.

◆ getGeometryData() [2/2]

template<typename _Manager >
const GeometryData& pinocchio::BroadPhaseManagerBase< Derived >::getGeometryData
inline

Returns the geometry data associated to the manager.

Definition at line 139 of file collision/broadphase-manager-base.hpp.

◆ getGeometryModel()

template<typename _Manager >
const GeometryModel& pinocchio::BroadPhaseManagerBase< Derived >::getGeometryModel
inline

Returns the geometry model associated to the manager.

Definition at line 133 of file collision/broadphase-manager-base.hpp.

◆ getModel()

template<typename _Manager >
const Model& pinocchio::BroadPhaseManagerBase< Derived >::getModel
inline

Returns the model associated to the manager.

Definition at line 127 of file collision/broadphase-manager-base.hpp.

◆ init()

template<typename _Manager >
void pinocchio::TreeBroadPhaseManagerTpl< _Manager >::init ( const size_t  njoints)
protected

Initialialisation.

◆ update() [1/2]

template<typename _Manager >
void pinocchio::TreeBroadPhaseManagerTpl< _Manager >::update ( bool  compute_local_aabb = false)

Update the manager from the current geometry positions and update the underlying FCL broad phase manager.

Parameters
[in]compute_local_aabbwhether to recompute the local AABB of the collision geometries which have changed.

◆ update() [2/2]

template<typename _Manager >
void pinocchio::TreeBroadPhaseManagerTpl< _Manager >::update ( GeometryData geom_data_ptr_new)

Update the manager with a new geometry data.

Parameters
[in]geom_data_ptr_newpointer to the new geometry data.

Member Data Documentation

◆ Manager

template<typename _Manager >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Manager pinocchio::TreeBroadPhaseManagerTpl< _Manager >::Manager

Definition at line 18 of file collision/tree-broadphase-manager.hpp.

◆ managers

template<typename _Manager >
BroadPhaseManagerVector pinocchio::TreeBroadPhaseManagerTpl< _Manager >::managers
protected

the vector of collision objects.

Definition at line 125 of file collision/tree-broadphase-manager.hpp.


The documentation for this struct was generated from the following files:


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:53