openrave.org

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Static Public Member Functions | List of all members
OpenRAVE::CollisionCheckerBase Class Referenceabstract

[interface] Responsible for all collision checking queries of the environment. If not specified, method is not multi-thread safe. See Collision Checker Concepts. More...

#include <collisionchecker.h>

Inheritance diagram for OpenRAVE::CollisionCheckerBase:
Inheritance graph
[legend]
Collaboration diagram for OpenRAVE::CollisionCheckerBase:
Collaboration graph
[legend]

Public Member Functions

 CollisionCheckerBase (EnvironmentBasePtr penv)
 
virtual ~CollisionCheckerBase ()
 
virtual bool SetCollisionOptions (int collisionoptions)=0
 Set basic collision options using the CollisionOptions enum.
 
virtual int GetCollisionOptions () const =0
 get the current collision options
 
virtual void SetTolerance (dReal tolerance)=0
 
virtual bool InitKinBody (KinBodyPtr pbody)=0
 notified when a new body has been initialized in the environment
 
- Public Member Functions inherited from OpenRAVE::InterfaceBase
 InterfaceBase (InterfaceType type, EnvironmentBasePtr penv)
 
virtual ~InterfaceBase ()
 
InterfaceType GetInterfaceType () const
 
const std::string & GetXMLId () const
 
const std::string & GetPluginName () const
 
EnvironmentBasePtr GetEnv () const
 
const READERSMAPGetReadableInterfaces () const
 
virtual XMLReadablePtr GetReadableInterface (const std::string &xmltag) const
 returns the readable interface
 
virtual XMLReadablePtr SetReadableInterface (const std::string &xmltag, XMLReadablePtr readable)
 set a new readable interface and return the previously set interface if it exists
 
virtual const std::string & GetDescription () const
 Documentation of the interface in reStructuredText format. See Documenting Interfaces.
 
virtual void SetDescription (const std::string &description)
 
virtual void SetUserData (UserDataPtr data)
 set user data
 
virtual void SetUserData (boost::shared_ptr< void > data) RAVE_DEPRECATED
 
virtual UserDataPtr GetUserData () const
 return the user custom data
 
virtual const std::string & GetURI () const
 the URI used to load the interface (sometimes this is not possible if the definition lies inside an environment file).
 
virtual const std::string & GetXMLFilename () const
 
virtual void Clone (InterfaceBaseConstPtr preference, int cloningoptions)
 Clone the contents of an interface to the current interface.
 
virtual bool SendCommand (std::ostream &os, std::istream &is)
 Used to send special commands to the interface and receive output.
 
virtual void Serialize (BaseXMLWriterPtr writer, int options=0) const
 serializes the interface
 

Static Public Member Functions

static InterfaceType GetInterfaceTypeStatic ()
 return the static interface type this class points to (used for safe casting)
 

Collision specific functions.

Each function takes an optional pointer to a CollisionReport structure and returns true if collision occurs.

virtual bool CheckCollision (KinBodyConstPtr pbody1, CollisionReportPtr report=CollisionReportPtr())=0
 checks collision of a body and a scene. Attached bodies are respected. If CO_ActiveDOFs is set, will only check affected links of the body.
 
virtual bool CheckCollision (KinBodyConstPtr pbody1, KinBodyConstPtr pbody2, CollisionReportPtr report=CollisionReportPtr())=0
 checks collision between two bodies. Attached bodies are respected. If CO_ActiveDOFs is set, will only check affected links of the pbody1.
 
virtual bool CheckCollision (KinBody::LinkConstPtr plink, CollisionReportPtr report=CollisionReportPtr())=0
 checks collision of a link and a scene. Attached bodies are ignored. CO_ActiveDOFs option is ignored.
 
virtual bool CheckCollision (KinBody::LinkConstPtr plink1, KinBody::LinkConstPtr plink2, CollisionReportPtr report=CollisionReportPtr())=0
 checks collision of two links. Attached bodies are ignored. CO_ActiveDOFs option is ignored.
 
virtual bool CheckCollision (KinBody::LinkConstPtr plink, KinBodyConstPtr pbody, CollisionReportPtr report=CollisionReportPtr())=0
 checks collision of a link and a body. Attached bodies for pbody are respected. CO_ActiveDOFs option is ignored.
 
virtual bool CheckCollision (KinBody::LinkConstPtr plink, const std::vector< KinBodyConstPtr > &vbodyexcluded, const std::vector< KinBody::LinkConstPtr > &vlinkexcluded, CollisionReportPtr report=CollisionReportPtr())=0
 checks collision of a link and a scene. Attached bodies are ignored. CO_ActiveDOFs option is ignored.
 
virtual bool CheckCollision (KinBodyConstPtr pbody, const std::vector< KinBodyConstPtr > &vbodyexcluded, const std::vector< KinBody::LinkConstPtr > &vlinkexcluded, CollisionReportPtr report=CollisionReportPtr())=0
 checks collision of a body and a scene. Attached bodies are respected. If CO_ActiveDOFs is set, will only check affected links of pbody.
 
virtual bool CheckCollision (const RAY &ray, KinBody::LinkConstPtr plink, CollisionReportPtr report=CollisionReportPtr())=0
 Check collision with a link and a ray with a specified length. CO_ActiveDOFs option is ignored.
 
virtual bool CheckCollision (const RAY &ray, KinBodyConstPtr pbody, CollisionReportPtr report=CollisionReportPtr())=0
 Check collision with a link and a ray with a specified length.
 
virtual bool CheckCollision (const RAY &ray, CollisionReportPtr report=CollisionReportPtr())=0
 Check collision with a body and a ray with a specified length. CO_ActiveDOFs option is ignored.
 
virtual bool InitEnvironment ()=0
 
virtual void DestroyEnvironment ()=0
 
virtual bool CheckSelfCollision (KinBodyConstPtr pbody, CollisionReportPtr report=CollisionReportPtr())=0
 Checks self collision only with the links of the passed in body.
 
virtual void SetCollisionData (KinBodyPtr pbody, UserDataPtr data)
 
CollisionCheckerBasePtr shared_collisionchecker ()
 
CollisionCheckerBaseConstPtr shared_collisionchecker_const () const
 

Additional Inherited Members

- Public Types inherited from OpenRAVE::InterfaceBase
typedef std::map< std::string,
XMLReadablePtr,
CaseInsensitiveCompare
READERSMAP
 
- Protected Types inherited from OpenRAVE::InterfaceBase
typedef boost::function< bool(std::ostream
&, std::istream &)> 
InterfaceCommandFn
 The function to be executed for every command.
 
- Protected Member Functions inherited from OpenRAVE::InterfaceBase
virtual void RegisterCommand (const std::string &cmdname, InterfaceCommandFn fncmd, const std::string &strhelp)
 Registers a command and its help string.
 
virtual void UnregisterCommand (const std::string &cmdname)
 Unregisters the command.
 
- Protected Attributes inherited from OpenRAVE::InterfaceBase
std::string __description
 

Detailed Description

[interface] Responsible for all collision checking queries of the environment. If not specified, method is not multi-thread safe. See Collision Checker Concepts.

Definition at line 95 of file collisionchecker.h.

Constructor & Destructor Documentation

OpenRAVE::CollisionCheckerBase::CollisionCheckerBase ( EnvironmentBasePtr  penv)
inline

Definition at line 98 of file collisionchecker.h.

virtual OpenRAVE::CollisionCheckerBase::~CollisionCheckerBase ( )
inlinevirtual

Definition at line 100 of file collisionchecker.h.

Member Function Documentation

virtual bool OpenRAVE::CollisionCheckerBase::CheckCollision ( KinBodyConstPtr  pbody1,
CollisionReportPtr  report = CollisionReportPtr() 
)
pure virtual

checks collision of a body and a scene. Attached bodies are respected. If CO_ActiveDOFs is set, will only check affected links of the body.

virtual bool OpenRAVE::CollisionCheckerBase::CheckCollision ( KinBodyConstPtr  pbody1,
KinBodyConstPtr  pbody2,
CollisionReportPtr  report = CollisionReportPtr() 
)
pure virtual

checks collision between two bodies. Attached bodies are respected. If CO_ActiveDOFs is set, will only check affected links of the pbody1.

virtual bool OpenRAVE::CollisionCheckerBase::CheckCollision ( KinBody::LinkConstPtr  plink,
CollisionReportPtr  report = CollisionReportPtr() 
)
pure virtual

checks collision of a link and a scene. Attached bodies are ignored. CO_ActiveDOFs option is ignored.

virtual bool OpenRAVE::CollisionCheckerBase::CheckCollision ( KinBody::LinkConstPtr  plink1,
KinBody::LinkConstPtr  plink2,
CollisionReportPtr  report = CollisionReportPtr() 
)
pure virtual

checks collision of two links. Attached bodies are ignored. CO_ActiveDOFs option is ignored.

virtual bool OpenRAVE::CollisionCheckerBase::CheckCollision ( KinBody::LinkConstPtr  plink,
KinBodyConstPtr  pbody,
CollisionReportPtr  report = CollisionReportPtr() 
)
pure virtual

checks collision of a link and a body. Attached bodies for pbody are respected. CO_ActiveDOFs option is ignored.

virtual bool OpenRAVE::CollisionCheckerBase::CheckCollision ( KinBody::LinkConstPtr  plink,
const std::vector< KinBodyConstPtr > &  vbodyexcluded,
const std::vector< KinBody::LinkConstPtr > &  vlinkexcluded,
CollisionReportPtr  report = CollisionReportPtr() 
)
pure virtual

checks collision of a link and a scene. Attached bodies are ignored. CO_ActiveDOFs option is ignored.

virtual bool OpenRAVE::CollisionCheckerBase::CheckCollision ( KinBodyConstPtr  pbody,
const std::vector< KinBodyConstPtr > &  vbodyexcluded,
const std::vector< KinBody::LinkConstPtr > &  vlinkexcluded,
CollisionReportPtr  report = CollisionReportPtr() 
)
pure virtual

checks collision of a body and a scene. Attached bodies are respected. If CO_ActiveDOFs is set, will only check affected links of pbody.

virtual bool OpenRAVE::CollisionCheckerBase::CheckCollision ( const RAY ray,
KinBody::LinkConstPtr  plink,
CollisionReportPtr  report = CollisionReportPtr() 
)
pure virtual

Check collision with a link and a ray with a specified length. CO_ActiveDOFs option is ignored.

Parameters
rayholds the origin and direction. The length of the ray is the length of the direction.
plinkthe link to collide with
[out]report[optional] collision report to be filled with data about the collision. If a body was hit, CollisionReport::plink1 contains the hit link pointer.
virtual bool OpenRAVE::CollisionCheckerBase::CheckCollision ( const RAY ray,
KinBodyConstPtr  pbody,
CollisionReportPtr  report = CollisionReportPtr() 
)
pure virtual

Check collision with a link and a ray with a specified length.

Parameters
rayholds the origin and direction. The length of the ray is the length of the direction.
pbodythe link to collide with. If CO_ActiveDOFs is set, will only check affected links of the body.
[out]report[optional] collision report to be filled with data about the collision. If a body was hit, CollisionReport::plink1 contains the hit link pointer.
virtual bool OpenRAVE::CollisionCheckerBase::CheckCollision ( const RAY ray,
CollisionReportPtr  report = CollisionReportPtr() 
)
pure virtual

Check collision with a body and a ray with a specified length. CO_ActiveDOFs option is ignored.

Parameters
rayholds the origin and direction. The length of the ray is the length of the direction.
pbodythe kinbody to look for collisions
[out]report[optional] collision report to be filled with data about the collision. If a body was hit, CollisionReport::plink1 contains the hit link pointer.
virtual bool OpenRAVE::CollisionCheckerBase::CheckSelfCollision ( KinBodyConstPtr  pbody,
CollisionReportPtr  report = CollisionReportPtr() 
)
protectedpure virtual

Checks self collision only with the links of the passed in body.

Links that are joined together are ignored.

virtual void OpenRAVE::CollisionCheckerBase::DestroyEnvironment ( )
protectedpure virtual

called when environment switches to a different collision checker engine has to clear/deallocate any memory associated with KinBody::_pCollisionData

virtual int OpenRAVE::CollisionCheckerBase::GetCollisionOptions ( ) const
pure virtual

get the current collision options

static InterfaceType OpenRAVE::CollisionCheckerBase::GetInterfaceTypeStatic ( )
inlinestatic

return the static interface type this class points to (used for safe casting)

Definition at line 104 of file collisionchecker.h.

virtual bool OpenRAVE::CollisionCheckerBase::InitEnvironment ( )
protectedpure virtual

called when environment sets this collision checker, checker assumes responsibility for KinBody::_pCollisionData checker should also gather all current bodies in the environment and put them in its collision space

virtual bool OpenRAVE::CollisionCheckerBase::InitKinBody ( KinBodyPtr  pbody)
pure virtual

notified when a new body has been initialized in the environment

virtual void OpenRAVE::CollisionCheckerBase::SetCollisionData ( KinBodyPtr  pbody,
UserDataPtr  data 
)
inlineprotectedvirtual

Definition at line 180 of file collisionchecker.h.

virtual bool OpenRAVE::CollisionCheckerBase::SetCollisionOptions ( int  collisionoptions)
pure virtual

Set basic collision options using the CollisionOptions enum.

virtual void OpenRAVE::CollisionCheckerBase::SetTolerance ( dReal  tolerance)
pure virtual
CollisionCheckerBasePtr OpenRAVE::CollisionCheckerBase::shared_collisionchecker ( )
inlineprotected

Definition at line 184 of file collisionchecker.h.

CollisionCheckerBaseConstPtr OpenRAVE::CollisionCheckerBase::shared_collisionchecker_const ( ) const
inlineprotected

Definition at line 187 of file collisionchecker.h.


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