Namespaces | Classes | Typedefs | Functions
collision_detection Namespace Reference

Generic interface to collision detection. More...

Namespaces

namespace  AllowedCollision
 

Any pair of bodies can have a collision state associated to it.


namespace  BodyTypes
 

The types of bodies that are considered for collision.


Classes

class  AllowedCollisionMatrix
 Definition of a structure for the allowed collision matrix. All elements in the collision world are referred to by their names. This class represents which collisions are allowed to happen and which are not. More...
struct  CollisionData
class  CollisionDetectorAllocator
 An allocator for a compatible CollisionWorld/CollisionRobot pair. More...
class  CollisionDetectorAllocatorAllValid
 An allocator for AllValid collision detectors. More...
class  CollisionDetectorAllocatorFCL
 An allocator for FCL collision detectors. More...
class  CollisionDetectorAllocatorTemplate
 Template class to make it easy to create an allocator for a specific CollisionWorld/CollisionRobot pair. More...
struct  CollisionGeometryData
struct  CollisionRequest
 Representation of a collision checking request. More...
struct  CollisionResult
 Representation of a collision checking result. More...
class  CollisionRobot
 This class represents a collision model of the robot and can be used for self collision checks (to check if the robot is in collision with itself) or in collision checks with a different robot. Collision checks with the environment are performed using the CollisionWorld class. More...
class  CollisionRobotAllValid
class  CollisionRobotFCL
class  CollisionWorld
 Perform collision checking with the environment. The collision world maintains a representation of the environment that the robot is operating in. More...
class  CollisionWorldAllValid
class  CollisionWorldFCL
struct  Contact
 Definition of a contact point. More...
struct  CostSource
 When collision costs are computed, this structure contains information about the partial cost incurred in a particular volume. More...
struct  FCLGeometry
struct  FCLManager
struct  FCLObject
struct  FCLShapeCache
struct  IfSameType
struct  IfSameType< T, T >
class  World
 Maintain a representation of the environment. More...
class  WorldDiff
 Maintain a diff list of changes that have happened to a World. More...

Typedefs

typedef boost::shared_ptr
< const AllowedCollisionMatrix
AllowedCollisionMatrixConstPtr
typedef boost::shared_ptr
< AllowedCollisionMatrix
AllowedCollisionMatrixPtr
typedef BodyTypes::Type BodyType
 The types of bodies that are considered for collision.
typedef boost::shared_ptr
< CollisionDetectorAllocator
CollisionDetectorAllocatorPtr
typedef boost::shared_ptr
< const CollisionRobot
CollisionRobotConstPtr
typedef boost::shared_ptr
< CollisionRobot
CollisionRobotPtr
typedef boost::shared_ptr
< const CollisionWorld
CollisionWorldConstPtr
typedef boost::shared_ptr
< CollisionWorld
CollisionWorldPtr
typedef boost::function< bool(collision_detection::Contact &)> DecideContactFn
 Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type is CONDITIONAL)
typedef boost::shared_ptr
< const FCLGeometry
FCLGeometryConstPtr
typedef boost::shared_ptr
< FCLGeometry
FCLGeometryPtr
typedef boost::shared_ptr
< const World
WorldConstPtr
typedef boost::shared_ptr
< const WorldDiff
WorldDiffConstPtr
typedef boost::shared_ptr
< WorldDiff
WorldDiffPtr
typedef boost::shared_ptr< WorldWorldPtr

Functions

static bool andDecideContact (const DecideContactFn &f1, const DecideContactFn &f2, collision_detection::Contact &contact)
void cleanCollisionGeometryCache ()
bool collisionCallback (fcl::CollisionObject *o1, fcl::CollisionObject *o2, void *data)
void contactToMsg (const Contact &contact, moveit_msgs::ContactInformation &msg)
void costSourceToMsg (const CostSource &cost_source, moveit_msgs::CostSource &msg)
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const robot_model::LinkModel *link)
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const robot_state::AttachedBody *ab)
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const World::Object *obj)
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const robot_model::LinkModel *link)
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const robot_state::AttachedBody *ab)
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const World::Object *obj)
template<typename BV , typename T >
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const T *data)
template<typename BV , typename T >
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const T *data)
bool distanceCallback (fcl::CollisionObject *o1, fcl::CollisionObject *o2, void *data, double &min_dist)
void fcl2contact (const fcl::Contact &fc, Contact &c)
void fcl2costsource (const fcl::CostSource &fcs, CostSource &cs)
void getCollisionMarkersFromContacts (visualization_msgs::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con, const std_msgs::ColorRGBA &color, const ros::Duration &lifetime, const double radius=0.035)
void getCollisionMarkersFromContacts (visualization_msgs::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con)
void getCostMarkers (visualization_msgs::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources)
void getCostMarkers (visualization_msgs::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources, const std_msgs::ColorRGBA &color, const ros::Duration &lifetime)
bool getSensorPositioning (geometry_msgs::Point &point, const std::set< CostSource > &cost_sources)
template<typename BV , typename T >
FCLShapeCacheGetShapeCache ()
double getTotalCost (const std::set< CostSource > &cost_sources)
void intersectCostSources (std::set< CostSource > &cost_sources, const std::set< CostSource > &a, const std::set< CostSource > &b)
int refineContactNormals (const World::ObjectConstPtr &object, CollisionResult &res, double cell_bbx_search_distance=1.0, double allowed_angle_divergence=0.0, bool estimate_depth=false, double iso_value=0.5, double metaball_radius_multiple=1.5)
 Re-proceses contact normals for an octomap by estimating a metaball iso-surface using the centers of occupied cells in a neighborhood of the contact point.
void removeCostSources (std::set< CostSource > &cost_sources, const std::set< CostSource > &cost_sources_to_remove, double overlap_fraction)
void removeOverlapping (std::set< CostSource > &cost_sources, double overlap_fraction)
void transform2fcl (const Eigen::Affine3d &b, fcl::Transform3f &f)
fcl::Transform3f transform2fcl (const Eigen::Affine3d &b)

Detailed Description

Generic interface to collision detection.

Author Ioan Sucan


Typedef Documentation

Definition at line 247 of file collision_matrix.h.

Definition at line 246 of file collision_matrix.h.

The types of bodies that are considered for collision.

Definition at line 69 of file include/moveit/collision_detection/collision_common.h.

Definition at line 67 of file collision_detector_allocator.h.

Definition at line 257 of file collision_robot.h.

Definition at line 256 of file collision_robot.h.

Definition at line 243 of file collision_world.h.

Definition at line 242 of file collision_world.h.

Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type is CONDITIONAL)

Definition at line 72 of file collision_matrix.h.

typedef boost::shared_ptr<const FCLGeometry> collision_detection::FCLGeometryConstPtr
typedef boost::shared_ptr<const World> collision_detection::WorldConstPtr

Definition at line 255 of file world.h.

typedef boost::shared_ptr<const WorldDiff> collision_detection::WorldDiffConstPtr

Definition at line 128 of file world_diff.h.

typedef boost::shared_ptr<WorldDiff> collision_detection::WorldDiffPtr

Definition at line 127 of file world_diff.h.

typedef boost::shared_ptr<World> collision_detection::WorldPtr

Definition at line 254 of file world.h.


Function Documentation

static bool collision_detection::andDecideContact ( const DecideContactFn &  f1,
const DecideContactFn &  f2,
collision_detection::Contact contact 
) [static]

Definition at line 254 of file collision_matrix.cpp.

Definition at line 711 of file collision_common.cpp.

bool collision_detection::collisionCallback ( fcl::CollisionObject *  o1,
fcl::CollisionObject *  o2,
void *  data 
)

Definition at line 46 of file collision_common.cpp.

void collision_detection::contactToMsg ( const Contact &  contact,
moveit_msgs::ContactInformation &  msg 
)

Definition at line 271 of file collision_tools.cpp.

void collision_detection::costSourceToMsg ( const CostSource &  cost_source,
moveit_msgs::CostSource &  msg 
)

Definition at line 260 of file collision_tools.cpp.

Definition at line 662 of file collision_common.cpp.

Definition at line 668 of file collision_common.cpp.

Definition at line 674 of file collision_common.cpp.

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
double  scale,
double  padding,
const robot_model::LinkModel link 
)

Definition at line 693 of file collision_common.cpp.

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
double  scale,
double  padding,
const robot_state::AttachedBody ab 
)

Definition at line 699 of file collision_common.cpp.

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
double  scale,
double  padding,
const World::Object *  obj 
)

Definition at line 705 of file collision_common.cpp.

template<typename BV , typename T >
FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
const T *  data 
)

Definition at line 475 of file collision_common.cpp.

template<typename BV , typename T >
FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
double  scale,
double  padding,
const T *  data 
)

Definition at line 681 of file collision_common.cpp.

bool collision_detection::distanceCallback ( fcl::CollisionObject *  o1,
fcl::CollisionObject *  o2,
void *  data,
double &  min_dist 
)

Definition at line 356 of file collision_common.cpp.

void collision_detection::fcl2contact ( const fcl::Contact &  fc,
Contact &  c 
) [inline]
void collision_detection::fcl2costsource ( const fcl::CostSource &  fcs,
CostSource &  cs 
) [inline]
void collision_detection::getCollisionMarkersFromContacts ( visualization_msgs::MarkerArray &  arr,
const std::string &  frame_id,
const CollisionResult::ContactMap &  con,
const std_msgs::ColorRGBA &  color,
const ros::Duration lifetime,
const double  radius = 0.035 
)

Definition at line 90 of file collision_tools.cpp.

void collision_detection::getCollisionMarkersFromContacts ( visualization_msgs::MarkerArray &  arr,
const std::string &  frame_id,
const CollisionResult::ContactMap &  con 
)

Definition at line 47 of file collision_tools.cpp.

void collision_detection::getCostMarkers ( visualization_msgs::MarkerArray &  arr,
const std::string &  frame_id,
std::set< CostSource > &  cost_sources 
)
Todo:
add a class for managing cost sources

Definition at line 40 of file collision_tools.cpp.

void collision_detection::getCostMarkers ( visualization_msgs::MarkerArray &  arr,
const std::string &  frame_id,
std::set< CostSource > &  cost_sources,
const std_msgs::ColorRGBA &  color,
const ros::Duration lifetime 
)

Definition at line 56 of file collision_tools.cpp.

bool collision_detection::getSensorPositioning ( geometry_msgs::Point &  point,
const std::set< CostSource > &  cost_sources 
)

Definition at line 132 of file collision_tools.cpp.

template<typename BV , typename T >
FCLShapeCache& collision_detection::GetShapeCache ( )

Definition at line 456 of file collision_common.cpp.

double collision_detection::getTotalCost ( const std::set< CostSource > &  cost_sources)

Definition at line 146 of file collision_tools.cpp.

void collision_detection::intersectCostSources ( std::set< CostSource > &  cost_sources,
const std::set< CostSource > &  a,
const std::set< CostSource > &  b 
)

Definition at line 155 of file collision_tools.cpp.

int collision_detection::refineContactNormals ( const World::ObjectConstPtr &  object,
CollisionResult &  res,
double  cell_bbx_search_distance = 1.0,
double  allowed_angle_divergence = 0.0,
bool  estimate_depth = false,
double  iso_value = 0.5,
double  metaball_radius_multiple = 1.5 
)

Re-proceses contact normals for an octomap by estimating a metaball iso-surface using the centers of occupied cells in a neighborhood of the contact point.

This is an implementation of the algorithm described in: A. Leeper, S. Chan, K. Salisbury. Point Clouds Can Be Represented as Implicit Surfaces for Constraint-Based Haptic Rendering. ICRA, May 2012, St Paul, MN. http://adamleeper.com/research/papers/2012_ICRA_leeper-chan-salisbury.pdf

Parameters:
Theoctomap originally used for collision detection.
Thecollision result (which will get its normals updated)
Thedistance, as a multiple of the octomap cell size, from which to include neighboring cells.
Theminimum angle change required for a normal to be over-written
Whetherto request a depth estimate from the algorithm (experimental...)
Theiso-surface threshold value (0.5 is a reasonable default).
Themetaball radius, as a multiple of the octomap cell size (1.5 is a reasonable default)

Definition at line 73 of file collision_octomap_filter.cpp.

void collision_detection::removeCostSources ( std::set< CostSource > &  cost_sources,
const std::set< CostSource > &  cost_sources_to_remove,
double  overlap_fraction 
)

Definition at line 208 of file collision_tools.cpp.

void collision_detection::removeOverlapping ( std::set< CostSource > &  cost_sources,
double  overlap_fraction 
)

Definition at line 177 of file collision_tools.cpp.

void collision_detection::transform2fcl ( const Eigen::Affine3d &  b,
fcl::Transform3f &  f 
) [inline]
fcl::Transform3f collision_detection::transform2fcl ( const Eigen::Affine3d &  b) [inline]


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:47