collision_space::EnvironmentModelBullet Class Reference

A class describing an environment for a kinematic robot using bullet. This class is still experimental, and methos such as cloning are not implemented. More...

#include <environmentBullet.h>

Inheritance diagram for collision_space::EnvironmentModelBullet:
Inheritance graph
[legend]

List of all members.

Classes

class  CollisionDispatcher
struct  GenericCollisionFilterCallback
struct  kGeom
struct  ModelInfo
struct  SelfCollisionFilterCallback

Public Member Functions

virtual void addObject (const std::string &ns, shapes::Shape *shape, const btTransform &pose)
 Add a collision object to the map. The user releases ownership of the passed object. Memory allocated for the shape is freed by the collision environment.
virtual void addObject (const std::string &ns, shapes::StaticShape *shape)
 Add a static collision object to the map. The user releases ownership of the passed object. Memory allocated for the shape is freed by the collision environment.
virtual void addObjects (const std::string &ns, const std::vector< shapes::Shape * > &shapes, const std::vector< btTransform > &poses)
 Add a set of collision objects to the map. The user releases ownership of the passed objects. Memory allocated for the shapes is freed by the collision environment.
virtual void clearObjects (const std::string &ns)
 Remove objects from a specific namespace in the collision model.
virtual void clearObjects (void)
 Remove all objects from collision model.
virtual EnvironmentModelclone (void) const
 Clone the environment.
 EnvironmentModelBullet (void)
virtual const std::vector
< const
planning_models::KinematicModel::AttachedBodyModel * > 
getAttachedBodies (void) const
 Gets a vector of all the bodies currently attached to the robot.
virtual bool getCollisionContacts (const std::vector< AllowedContact > &allowedContacts, std::vector< Contact > &contacts, unsigned int max_count=1)
 Get the list of contacts (collisions).
virtual bool isCollision (void)
 Check if a model is in collision.
virtual bool isSelfCollision (void)
 Check if a model is in self collision.
virtual void removeCollidingObjects (const shapes::Shape *shape, const btTransform &pose)
 Remove objects in the collision space that are collising with the object supplied as argument.
virtual void removeCollidingObjects (const shapes::StaticShape *shape)
 Remove objects in the collision space that are collising with the object supplied as argument.
virtual int setCollisionCheck (const std::string &link, bool state)
 Enable/Disable collision checking for specific links. Return the previous value of the state (1 or 0) if succesful; -1 otherwise.
void setCollisionCheckAll (bool state)
 Set collision checking for all links to state.
void setCollisionCheckLinks (const std::vector< std::string > &links, bool state)
 Enable/Disable collision checking for a set of links.
void setCollisionCheckOnlyLinks (const std::vector< std::string > &links, bool state)
 Set collision checking for the set of links to state, set collision checking for all other links to !state.
virtual void setRobotModel (const boost::shared_ptr< const planning_models::KinematicModel > &model, const std::vector< std::string > &links, const std::map< std::string, double > &link_padding_map, double default_padding=0.0, double scale=1.0)
 Add a robot model. Ignore robot links if their name is not specified in the string vector. The scale argument can be used to increase or decrease the size of the robot's bodies (multiplicative factor). The padding can be used to increase or decrease the robot's bodies with by an additive term.
virtual void updateAttachedBodies (void)
 Update the set of bodies that are attached to the robot (re-creates them).
virtual void updateRobotModel (void)
 Update the positions of the geometry used in collision detection.
virtual ~EnvironmentModelBullet (void)

Protected Member Functions

btCollisionObject * createCollisionBody (const shapes::StaticShape *shape)
btCollisionObject * createCollisionBody (const shapes::Shape *shape, double scale, double padding)
void freeMemory (void)

Protected Attributes

btDefaultCollisionConfiguration * m_config
GenericCollisionFilterCallback m_genericCollisionFilterCallback
ModelInfo m_modelGeom
std::map< std::string,
std::vector< btCollisionObject * > > 
m_obstacles
SelfCollisionFilterCallback m_selfCollisionFilterCallback
btCollisionWorld * m_world

Detailed Description

A class describing an environment for a kinematic robot using bullet. This class is still experimental, and methos such as cloning are not implemented.

Definition at line 46 of file environmentBullet.h.


Constructor & Destructor Documentation

collision_space::EnvironmentModelBullet::EnvironmentModelBullet ( void   )  [inline]

Definition at line 46 of file environmentBullet.h.

virtual collision_space::EnvironmentModelBullet::~EnvironmentModelBullet ( void   )  [inline, virtual]

Definition at line 56 of file environmentBullet.h.


Member Function Documentation

void collision_space::EnvironmentModelBullet::addObject ( const std::string &  ns,
shapes::Shape *  shape,
const btTransform &  pose 
) [virtual]

Add a collision object to the map. The user releases ownership of the passed object. Memory allocated for the shape is freed by the collision environment.

Implements collision_space::EnvironmentModel.

Definition at line 342 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::addObject ( const std::string &  ns,
shapes::StaticShape *  shape 
) [virtual]

Add a static collision object to the map. The user releases ownership of the passed object. Memory allocated for the shape is freed by the collision environment.

Implements collision_space::EnvironmentModel.

Definition at line 334 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::addObjects ( const std::string &  ns,
const std::vector< shapes::Shape * > &  shapes,
const std::vector< btTransform > &  poses 
) [virtual]

Add a set of collision objects to the map. The user releases ownership of the passed objects. Memory allocated for the shapes is freed by the collision environment.

Implements collision_space::EnvironmentModel.

Definition at line 327 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::clearObjects ( const std::string &  ns  )  [virtual]

Remove objects from a specific namespace in the collision model.

Implements collision_space::EnvironmentModel.

Definition at line 351 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::clearObjects ( void   )  [virtual]

Remove all objects from collision model.

Implements collision_space::EnvironmentModel.

Definition at line 368 of file environmentBullet.cpp.

collision_space::EnvironmentModel * collision_space::EnvironmentModelBullet::clone ( void   )  const [virtual]

Clone the environment.

Implements collision_space::EnvironmentModel.

Definition at line 438 of file environmentBullet.cpp.

btCollisionObject * collision_space::EnvironmentModelBullet::createCollisionBody ( const shapes::StaticShape *  shape  )  [protected]

Definition at line 171 of file environmentBullet.cpp.

btCollisionObject * collision_space::EnvironmentModelBullet::createCollisionBody ( const shapes::Shape *  shape,
double  scale,
double  padding 
) [protected]

Definition at line 121 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::freeMemory ( void   )  [protected]
Author:
Ioan Sucan

Definition at line 39 of file environmentBullet.cpp.

const std::vector< const planning_models::KinematicModel::AttachedBody * > collision_space::EnvironmentModelBullet::getAttachedBodies ( void   )  const [virtual]

Gets a vector of all the bodies currently attached to the robot.

Implements collision_space::EnvironmentModel.

Definition at line 102 of file environmentBullet.cpp.

bool collision_space::EnvironmentModelBullet::getCollisionContacts ( const std::vector< AllowedContact > &  allowedContacts,
std::vector< Contact > &  contacts,
unsigned int  max_count = 1 
) [virtual]

Get the list of contacts (collisions).

Implements collision_space::EnvironmentModel.

Definition at line 257 of file environmentBullet.cpp.

bool collision_space::EnvironmentModelBullet::isCollision ( void   )  [virtual]

Check if a model is in collision.

Implements collision_space::EnvironmentModel.

Definition at line 240 of file environmentBullet.cpp.

bool collision_space::EnvironmentModelBullet::isSelfCollision ( void   )  [virtual]

Check if a model is in self collision.

Implements collision_space::EnvironmentModel.

Definition at line 302 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::removeCollidingObjects ( const shapes::Shape *  shape,
const btTransform &  pose 
) [virtual]

Remove objects in the collision space that are collising with the object supplied as argument.

Implements collision_space::EnvironmentModel.

Definition at line 323 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::removeCollidingObjects ( const shapes::StaticShape *  shape  )  [virtual]

Remove objects in the collision space that are collising with the object supplied as argument.

Implements collision_space::EnvironmentModel.

Definition at line 319 of file environmentBullet.cpp.

int collision_space::EnvironmentModelBullet::setCollisionCheck ( const std::string &  link,
bool  state 
) [virtual]

Enable/Disable collision checking for specific links. Return the previous value of the state (1 or 0) if succesful; -1 otherwise.

Implements collision_space::EnvironmentModel.

Definition at line 374 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::setCollisionCheckAll ( bool  state  )  [virtual]

Set collision checking for all links to state.

Implements collision_space::EnvironmentModel.

Definition at line 430 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::setCollisionCheckLinks ( const std::vector< std::string > &  links,
bool  state 
) [virtual]

Enable/Disable collision checking for a set of links.

Implements collision_space::EnvironmentModel.

Definition at line 390 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::setCollisionCheckOnlyLinks ( const std::vector< std::string > &  links,
bool  state 
) [virtual]

Set collision checking for the set of links to state, set collision checking for all other links to !state.

Implements collision_space::EnvironmentModel.

Definition at line 408 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::setRobotModel ( const boost::shared_ptr< const planning_models::KinematicModel > &  model,
const std::vector< std::string > &  links,
const std::map< std::string, double > &  link_padding_map,
double  default_padding = 0.0,
double  scale = 1.0 
) [virtual]

Add a robot model. Ignore robot links if their name is not specified in the string vector. The scale argument can be used to increase or decrease the size of the robot's bodies (multiplicative factor). The padding can be used to increase or decrease the robot's bodies with by an additive term.

Reimplemented from collision_space::EnvironmentModel.

Definition at line 62 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::updateAttachedBodies ( void   )  [virtual]

Update the set of bodies that are attached to the robot (re-creates them).

Implements collision_space::EnvironmentModel.

Definition at line 198 of file environmentBullet.cpp.

void collision_space::EnvironmentModelBullet::updateRobotModel ( void   )  [virtual]

Update the positions of the geometry used in collision detection.

Definition at line 228 of file environmentBullet.cpp.


Member Data Documentation

btDefaultCollisionConfiguration* collision_space::EnvironmentModelBullet::m_config [protected]

Definition at line 261 of file environmentBullet.h.

Definition at line 255 of file environmentBullet.h.

Definition at line 257 of file environmentBullet.h.

std::map<std::string, std::vector<btCollisionObject*> > collision_space::EnvironmentModelBullet::m_obstacles [protected]

Definition at line 259 of file environmentBullet.h.

Definition at line 254 of file environmentBullet.h.

btCollisionWorld* collision_space::EnvironmentModelBullet::m_world [protected]

Definition at line 260 of file environmentBullet.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Friends


collision_space
Author(s): Ioan Sucan/isucan@willowgarage.com
autogenerated on Fri Jan 11 10:01:26 2013