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

#include <broadphase-manager.hpp>

Inheritance diagram for pinocchio::BroadPhaseManagerTpl< _Manager >:
Inheritance graph
[legend]

Public Types

typedef std::vector< CollisionObjectCollisionObjectVector
 
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 VectorXsgetCollisionObjectInflation ()
 Returns the inflation value related to each collision object. More...
 
CollisionObjectVectorgetCollisionObjects ()
 Returns the vector of collision objects associated to the manager. More...
 
const CollisionObjectVectorgetCollisionObjects () 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...
 
ManagergetManager ()
 Returns internal manager. More...
 
const ManagergetManager () 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
 
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...
 
BroadPhaseManagerBaseoperator= (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 > >
GeometryDatageometry_data_ptr
 Pointer to the geometry data. More...
 
const GeometryModelgeometry_model_ptr
 Pointer to the geometry model. More...
 
const Modelmodel_ptr
 Pointer to the model. More...
 

Detailed Description

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

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

Member Typedef Documentation

◆ CollisionObjectVector

template<typename _Manager >
typedef std::vector<CollisionObject> pinocchio::BroadPhaseManagerTpl< _Manager >::CollisionObjectVector

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

◆ GeometryData

template<typename _Manager >
typedef ::pinocchio::GeometryData pinocchio::BroadPhaseManagerTpl< _Manager >::GeometryData

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

◆ GeometryModel

template<typename _Manager >
typedef ::pinocchio::GeometryModel pinocchio::BroadPhaseManagerTpl< _Manager >::GeometryModel

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

◆ Manager

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

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

◆ Model

template<typename _Manager >
typedef ::pinocchio::Model pinocchio::BroadPhaseManagerTpl< _Manager >::Model

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

◆ VectorXs

template<typename _Manager >
typedef Eigen::VectorXd pinocchio::BroadPhaseManagerTpl< _Manager >::VectorXs

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

Constructor & Destructor Documentation

◆ BroadPhaseManagerTpl() [1/3]

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

Default constructor.

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

◆ BroadPhaseManagerTpl() [2/3]

template<typename _Manager >
pinocchio::BroadPhaseManagerTpl< _Manager >::BroadPhaseManagerTpl ( const Model model_ptr,
const GeometryModel geometry_model_ptr,
GeometryData geometry_data_ptr,
const GeometryObjectFilterBase filter = GeometryObjectFilterNothing() 
)
inline

Constructor from a given geometry model and data.

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

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

◆ BroadPhaseManagerTpl() [3/3]

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

Copy contructor.

Parameters
[in]othermanager to copy.

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

◆ ~BroadPhaseManagerTpl()

template<typename _Manager >
pinocchio::BroadPhaseManagerTpl< _Manager >::~BroadPhaseManagerTpl ( )

Member Function Documentation

◆ check() [1/2]

template<typename _Manager >
bool pinocchio::BroadPhaseManagerTpl< _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::BroadPhaseManagerTpl< _Manager >::check ( CollisionCallBackBase callback) const

Check whether the callback is inline with *this.

◆ collide() [1/3]

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

Performs collision test with objects belonging to another manager.

◆ collide() [2/3]

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

Performs collision test for the objects belonging to the manager.

◆ collide() [3/3]

template<typename _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.

◆ getCollisionObjectInflation()

template<typename _Manager >
const VectorXs& pinocchio::BroadPhaseManagerTpl< _Manager >::getCollisionObjectInflation ( )
inline

Returns the inflation value related to each collision object.

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

◆ getCollisionObjects() [1/2]

template<typename _Manager >
CollisionObjectVector& pinocchio::BroadPhaseManagerTpl< _Manager >::getCollisionObjects ( )
inline

Returns the vector of collision objects associated to the manager.

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

◆ getCollisionObjects() [2/2]

template<typename _Manager >
const CollisionObjectVector& pinocchio::BroadPhaseManagerTpl< _Manager >::getCollisionObjects ( ) const
inline

Returns the vector of collision objects associated to the manager.

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

◆ getCollisionObjectStatus()

template<typename _Manager >
const std::vector<bool>& pinocchio::BroadPhaseManagerTpl< _Manager >::getCollisionObjectStatus ( ) const
inline

Returns the status of the collision object.

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

◆ getManager() [1/2]

template<typename _Manager >
Manager& pinocchio::BroadPhaseManagerTpl< _Manager >::getManager ( )
inline

Returns internal manager.

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

◆ getManager() [2/2]

template<typename _Manager >
const Manager& pinocchio::BroadPhaseManagerTpl< _Manager >::getManager ( ) const
inline

Returns internal manager.

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

◆ init()

template<typename _Manager >
void pinocchio::BroadPhaseManagerTpl< _Manager >::init ( )
protected

Initialialisation of BroadPhaseManagerTpl.

◆ update() [1/2]

template<typename _Manager >
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.

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::BroadPhaseManagerTpl< _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

◆ Base

template<typename _Manager >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef BroadPhaseManagerBase<BroadPhaseManagerTpl<_Manager> > pinocchio::BroadPhaseManagerTpl< _Manager >::Base

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

◆ collision_object_inflation

template<typename _Manager >
VectorXs pinocchio::BroadPhaseManagerTpl< _Manager >::collision_object_inflation
protected

the inflation value related to each collision object.

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

◆ collision_object_is_active

template<typename _Manager >
std::vector<bool> pinocchio::BroadPhaseManagerTpl< _Manager >::collision_object_is_active
protected

Disable status related to each collision objects.

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

◆ collision_objects

template<typename _Manager >
CollisionObjectVector pinocchio::BroadPhaseManagerTpl< _Manager >::collision_objects
protected

the vector of collision objects.

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

◆ geometry_to_collision_index

template<typename _Manager >
std::vector<size_t> pinocchio::BroadPhaseManagerTpl< _Manager >::geometry_to_collision_index
protected

Mapping between a given geometry index and a collision index.

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

◆ manager

template<typename _Manager >
Manager pinocchio::BroadPhaseManagerTpl< _Manager >::manager
protected

internal manager

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

◆ selected_collision_pairs

template<typename _Manager >
std::vector<size_t> pinocchio::BroadPhaseManagerTpl< _Manager >::selected_collision_pairs
protected

Selected collision pairs in the original geometry_model.

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

◆ selected_geometry_objects

template<typename _Manager >
std::vector<size_t> pinocchio::BroadPhaseManagerTpl< _Manager >::selected_geometry_objects
protected

Selected geometry objects in the original geometry_model.

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


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


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