moveit2
The MoveIt Motion Planning Framework for ROS 2.
Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
collision_detection Namespace Reference

Namespaces

 AllowedCollision
 Any pair of bodies can have a collision state associated to it.
 
 BodyTypes
 The types of bodies that are considered for collision.
 
 DistanceRequestTypes
 

Classes

class  CollisionDetectorAllocatorAllValid
 An allocator for AllValid collision detectors. More...
 
class  CollisionEnvAllValid
 Collision environment which always just returns no collisions. More...
 
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  CollisionResult
 Representation of a collision checking result. More...
 
struct  CollisionRequest
 Representation of a collision checking request. More...
 
struct  DistanceRequest
 Representation of a distance-reporting request. More...
 
struct  DistanceResultsData
 Generic representation of the distance information for a pair of objects. More...
 
struct  DistanceResult
 Result of a distance request. More...
 
class  CollisionDetectorAllocator
 An allocator for a compatible CollisionWorld/CollisionRobot pair. More...
 
class  CollisionDetectorAllocatorTemplate
 Template class to make it easy to create an allocator for a specific CollisionWorld/CollisionRobot pair. More...
 
class  CollisionEnv
 Provides the interface to the individual collision checking libraries. More...
 
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...
 
class  CollisionPlugin
 Plugin API for loading a custom collision detection robot/world. More...
 
class  CollisionPluginCache
 
class  OccMapTree
 
class  World
 Maintain a representation of the environment. More...
 
class  WorldDiff
 Maintain a diff list of changes that have happened to a World. More...
 
class  CollisionDetectorAllocatorBullet
 An allocator for Bullet collision detectors. More...
 
class  CollisionDetectorBtPluginLoader
 
class  CollisionEnvBullet
 
More...
 
struct  CollisionGeometryData
 Wrapper around world, link and attached objects' geometry data. More...
 
struct  CollisionData
 Data structure which is passed to the collision callback function of the collision manager. More...
 
struct  DistanceData
 Data structure which is passed to the distance callback function of the collision manager. More...
 
struct  FCLGeometry
 Bundles the CollisionGeometryData and FCL collision geometry representation into a single class. More...
 
struct  FCLObject
 A general high-level object which consists of multiple FCLCollisionObjects. It is the top level data structure which is used in the collision checking process. More...
 
struct  FCLManager
 Bundles an FCLObject and a broadphase FCL collision manager. More...
 
class  CollisionDetectorAllocatorFCL
 An allocator for FCL collision detectors. More...
 
class  CollisionDetectorFCLPluginLoader
 
class  CollisionEnvFCL
 FCL implementation of the CollisionEnv. More...
 
struct  FCLShapeCache
 Cache for an arbitrary type of shape. It is assigned during the execution of createCollisionGeometry(). More...
 
struct  GroupStateRepresentation
 
struct  DistanceFieldCacheEntry
 
class  CollisionDetectorAllocatorDistanceField
 An allocator for Distance Field collision detectors. More...
 
class  CollisionDetectorAllocatorHybrid
 An allocator for Hybrid collision detectors. More...
 
struct  CollisionSphere
 
struct  GradientInfo
 
class  PosedDistanceField
 
class  BodyDecomposition
 
class  PosedBodySphereDecomposition
 
class  PosedBodyPointDecomposition
 
class  PosedBodySphereDecompositionVector
 
class  PosedBodyPointDecompositionVector
 
struct  ProximityInfo
 
class  CollisionEnvDistanceField
 
class  CollisionEnvHybrid
 This hybrid collision environment combines FCL and a distance field. Both can be used to calculate collisions. More...
 
struct  BodyDecompositionCache
 
class  CollisionRobotDistanceFieldROS
 
class  CollisionRobotHybridROS
 
class  CollisionPluginLoader
 

Typedefs

using BodyType = BodyTypes::Type
 The types of bodies that are considered for collision. More...
 
using DistanceRequestType = DistanceRequestTypes::DistanceRequestType
 
using DistanceMap = std::map< const std::pair< std::string, std::string >, std::vector< DistanceResultsData > >
 Mapping between the names of the collision objects and the DistanceResultData. More...
 
using DecideContactFn = std::function< bool(collision_detection::Contact &)>
 Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type is CONDITIONAL) More...
 
typedef octomap::OcTreeNode OccMapNode
 
using OccMapTreePtr = std::shared_ptr< OccMapTree >
 
using OccMapTreeConstPtr = std::shared_ptr< const OccMapTree >
 
typedef std::shared_ptr< fcl::CollisionObjectdFCLCollisionObjectPtr
 
typedef std::shared_ptr< const fcl::CollisionObjectdFCLCollisionObjectConstPtr
 

Enumerations

enum  CollisionType { NONE = 0 , SELF = 1 , INTRA = 2 , ENVIRONMENT = 3 }
 

Functions

 MOVEIT_CLASS_FORWARD (AllowedCollisionMatrix)
 
 MOVEIT_CLASS_FORWARD (CollisionDetectorAllocator)
 
 MOVEIT_CLASS_FORWARD (CollisionEnv)
 
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. More...
 
 MOVEIT_CLASS_FORWARD (CollisionPlugin)
 
void getCollisionMarkersFromContacts (visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con, const std_msgs::msg::ColorRGBA &color, const rclcpp::Duration &lifetime, const double radius=0.035)
 
void getCollisionMarkersFromContacts (visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con)
 
void getCostMarkers (visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources)
 
void getCostMarkers (visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources, const std_msgs::msg::ColorRGBA &color, const rclcpp::Duration &lifetime)
 
double getTotalCost (const std::set< CostSource > &cost_sources)
 
void removeCostSources (std::set< CostSource > &cost_sources, const std::set< CostSource > &cost_sources_to_remove, double overlap_fraction)
 
void intersectCostSources (std::set< CostSource > &cost_sources, const std::set< CostSource > &a, const std::set< CostSource > &b)
 
void removeOverlapping (std::set< CostSource > &cost_sources, double overlap_fraction)
 
bool getSensorPositioning (geometry_msgs::msg::Point &point, const std::set< CostSource > &cost_sources)
 
void costSourceToMsg (const CostSource &cost_source, moveit_msgs::msg::CostSource &msg)
 
void contactToMsg (const Contact &contact, moveit_msgs::msg::ContactInformation &msg)
 
 MOVEIT_CLASS_FORWARD (World)
 
 MOVEIT_CLASS_FORWARD (WorldDiff)
 
 MOVEIT_STRUCT_FORWARD (CollisionGeometryData)
 
 MOVEIT_STRUCT_FORWARD (FCLGeometry)
 
bool collisionCallback (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
 Callback function used by the FCLManager used for each pair of collision objects to calculate object contact information. More...
 
bool distanceCallback (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data, double &min_dist)
 Callback function used by the FCLManager used for each pair of collision objects to calculate collisions and distances. More...
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const moveit::core::LinkModel *link, int shape_index)
 Create new FCLGeometry object out of robot link model. More...
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const moveit::core::AttachedBody *ab, int shape_index)
 Create new FCLGeometry object out of attached body. More...
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const World::Object *obj)
 Create new FCLGeometry object out of a world object. More...
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const moveit::core::LinkModel *link, int shape_index)
 Create new scaled and / or padded FCLGeometry object out of robot link model. More...
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const moveit::core::AttachedBody *ab, int shape_index)
 Create new scaled and / or padded FCLGeometry object out of an attached body. More...
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const World::Object *obj)
 Create new scaled and / or padded FCLGeometry object out of an world object. More...
 
void cleanCollisionGeometryCache ()
 Increases the counter of the caches which can trigger the cleaning of expired entries from them. More...
 
void transform2fcl (const Eigen::Isometry3d &b, fcl::Transform3d &f)
 Transforms an Eigen Isometry3d to FCL coordinate transformation. More...
 
fcl::Transform3d transform2fcl (const Eigen::Isometry3d &b)
 Transforms an Eigen Isometry3d to FCL coordinate transformation. More...
 
void fcl2contact (const fcl::Contactd &fc, Contact &c)
 Transforms an FCL contact into a MoveIt contact point. More...
 
void fcl2costsource (const fcl::CostSourced &fcs, CostSource &cs)
 Transforms the FCL internal representation to the MoveIt CostSource data structure. More...
 
template<typename BV , typename T >
FCLShapeCacheGetShapeCache ()
 
template<typename BV , typename T >
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const T *data, int shape_index)
 Templated helper function creating new collision geometry out of general object using an arbitrary bounding volume (BV). More...
 
template<typename BV , typename T >
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const T *data, int shape_index)
 Templated helper function creating new collision geometry out of general object using an arbitrary bounding volume (BV). This can include padding and scaling. More...
 
 MOVEIT_STRUCT_FORWARD (GroupStateRepresentation)
 
 MOVEIT_STRUCT_FORWARD (DistanceFieldCacheEntry)
 
BodyDecompositionConstPtr getBodyDecompositionCacheEntry (const shapes::ShapeConstPtr &shape, double resolution)
 
PosedBodyPointDecompositionVectorPtr getCollisionObjectPointDecomposition (const collision_detection::World::Object &obj, double resolution)
 
PosedBodySphereDecompositionVectorPtr getAttachedBodySphereDecomposition (const moveit::core::AttachedBody *att, double resolution)
 
PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition (const moveit::core::AttachedBody *att, double resolution)
 
void getBodySphereVisualizationMarkers (const GroupStateRepresentationPtr &gsr, const std::string &reference_frame, visualization_msgs::msg::MarkerArray &body_marker_array)
 
 MOVEIT_CLASS_FORWARD (PosedDistanceField)
 
 MOVEIT_CLASS_FORWARD (BodyDecomposition)
 
 MOVEIT_CLASS_FORWARD (PosedBodySphereDecomposition)
 
 MOVEIT_CLASS_FORWARD (PosedBodyPointDecomposition)
 
 MOVEIT_CLASS_FORWARD (PosedBodySphereDecompositionVector)
 
 MOVEIT_CLASS_FORWARD (PosedBodyPointDecompositionVector)
 
std::vector< CollisionSpheredetermineCollisionSpheres (const bodies::Body *body, Eigen::Isometry3d &relativeTransform)
 
bool getCollisionSphereGradients (const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, GradientInfo &gradient, const CollisionType &type, double tolerance, bool subtract_radii, double maximum_value, bool stop_at_first_collision)
 
bool getCollisionSphereCollision (const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, double maximum_value, double tolerance)
 
bool getCollisionSphereCollision (const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, double maximum_value, double tolerance, unsigned int num_coll, std::vector< unsigned int > &colls)
 
bool doBoundingSpheresIntersect (const PosedBodySphereDecompositionConstPtr &p1, const PosedBodySphereDecompositionConstPtr &p2)
 
void getCollisionSphereMarkers (const std_msgs::msg::ColorRGBA &color, const std::string &frame_id, const std::string &ns, const rclcpp::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, visualization_msgs::msg::MarkerArray &arr)
 
void getProximityGradientMarkers (const std::string &frame_id, const std::string &ns, const rclcpp::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, const std::vector< PosedBodySphereDecompositionVectorPtr > &posed_vector_decompositions, const std::vector< GradientInfo > &gradients, visualization_msgs::msg::MarkerArray &arr)
 
void getCollisionMarkers (const std::string &frame_id, const std::string &ns, const rclcpp::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, const std::vector< PosedBodySphereDecompositionVectorPtr > &posed_vector_decompositions, const std::vector< GradientInfo > &gradients, visualization_msgs::msg::MarkerArray &arr)
 
 MOVEIT_CLASS_FORWARD (CollisionEnvDistanceField)
 
BodyDecompositionCachegetBodyDecompositionCache ()
 
void getBodySphereVisualizationMarkers (const GroupStateRepresentationConstPtr &gsr, const std::string &reference_frame, visualization_msgs::msg::MarkerArray &body_marker_array)
 

Variables

const double MAX_DISTANCE_MARGIN = 99
 
const double EPSILON = 0.001f
 

Detailed Description

Author
E. Gil Jones

Typedef Documentation

◆ BodyType

The types of bodies that are considered for collision.

Definition at line 70 of file collision_common.h.

◆ DecideContactFn

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

Definition at line 71 of file collision_matrix.h.

◆ DistanceMap

using collision_detection::DistanceMap = typedef std::map<const std::pair<std::string, std::string>, std::vector<DistanceResultsData> >

Mapping between the names of the collision objects and the DistanceResultData.

Definition at line 358 of file collision_common.h.

◆ DistanceRequestType

Definition at line 239 of file collision_common.h.

◆ FCLCollisionObjectConstPtr

Definition at line 251 of file collision_common.h.

◆ FCLCollisionObjectPtr

Definition at line 250 of file collision_common.h.

◆ OccMapNode

typedef octomap::OcTreeNode collision_detection::OccMapNode

Definition at line 49 of file occupancy_map.h.

◆ OccMapTreeConstPtr

using collision_detection::OccMapTreeConstPtr = typedef std::shared_ptr<const OccMapTree>

Definition at line 119 of file occupancy_map.h.

◆ OccMapTreePtr

using collision_detection::OccMapTreePtr = typedef std::shared_ptr<OccMapTree>

Definition at line 118 of file occupancy_map.h.

Enumeration Type Documentation

◆ CollisionType

Enumerator
NONE 
SELF 
INTRA 
ENVIRONMENT 

Definition at line 62 of file collision_distance_field_types.h.

Function Documentation

◆ cleanCollisionGeometryCache()

void collision_detection::cleanCollisionGeometryCache ( )

Increases the counter of the caches which can trigger the cleaning of expired entries from them.

Definition at line 922 of file collision_common.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ collisionCallback()

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

Callback function used by the FCLManager used for each pair of collision objects to calculate object contact information.

Parameters
o1First FCL collision object
o2Second FCL collision object \data General pointer to arbitrary data which is used during the callback
Returns
True terminates the collision check, false continues it to the next pair of objects

Definition at line 61 of file collision_common.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ contactToMsg()

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

Definition at line 276 of file collision_tools.cpp.

◆ costSourceToMsg()

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

Definition at line 265 of file collision_tools.cpp.

◆ createCollisionGeometry() [1/8]

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr &  shape,
const moveit::core::AttachedBody ab,
int  shape_index 
)

Create new FCLGeometry object out of attached body.

Definition at line 876 of file collision_common.cpp.

◆ createCollisionGeometry() [2/8]

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr &  shape,
const moveit::core::LinkModel link,
int  shape_index 
)

Create new FCLGeometry object out of robot link model.

Definition at line 870 of file collision_common.cpp.

Here is the caller graph for this function:

◆ createCollisionGeometry() [3/8]

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

Templated helper function creating new collision geometry out of general object using an arbitrary bounding volume (BV).

It assigns a thread-local cache for each type of shape and minimizes memory usage and copying through utilizing the cache.

Definition at line 692 of file collision_common.cpp.

Here is the call graph for this function:

◆ createCollisionGeometry() [4/8]

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr &  shape,
const World::Object obj 
)

Create new FCLGeometry object out of a world object.

A world object always consists only of a single shape, therefore we don't need the shape_index.

Definition at line 882 of file collision_common.cpp.

◆ createCollisionGeometry() [5/8]

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr &  shape,
double  scale,
double  padding,
const moveit::core::AttachedBody ab,
int  shape_index 
)

Create new scaled and / or padded FCLGeometry object out of an attached body.

Definition at line 910 of file collision_common.cpp.

◆ createCollisionGeometry() [6/8]

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr &  shape,
double  scale,
double  padding,
const moveit::core::LinkModel link,
int  shape_index 
)

Create new scaled and / or padded FCLGeometry object out of robot link model.

Definition at line 904 of file collision_common.cpp.

◆ createCollisionGeometry() [7/8]

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

Templated helper function creating new collision geometry out of general object using an arbitrary bounding volume (BV). This can include padding and scaling.

Definition at line 890 of file collision_common.cpp.

◆ createCollisionGeometry() [8/8]

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

Create new scaled and / or padded FCLGeometry object out of an world object.

Definition at line 916 of file collision_common.cpp.

◆ determineCollisionSpheres()

std::vector< CollisionSphere > collision_detection::determineCollisionSpheres ( const bodies::Body *  body,
Eigen::Isometry3d &  relativeTransform 
)

Definition at line 53 of file collision_distance_field_types.cpp.

Here is the caller graph for this function:

◆ distanceCallback()

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

Callback function used by the FCLManager used for each pair of collision objects to calculate collisions and distances.

Parameters
o1First FCL collision object
o2Second FCL collision object \data General pointer to arbitrary data which is used during the callback
Returns
True terminates the distance check, false continues it to the next pair of objects

Definition at line 412 of file collision_common.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ doBoundingSpheresIntersect()

bool collision_detection::doBoundingSpheresIntersect ( const PosedBodySphereDecompositionConstPtr &  p1,
const PosedBodySphereDecompositionConstPtr &  p2 
)

Definition at line 402 of file collision_distance_field_types.cpp.

Here is the caller graph for this function:

◆ fcl2contact()

void collision_detection::fcl2contact ( const fcl::Contactd fc,
Contact c 
)
inline

Transforms an FCL contact into a MoveIt contact point.

Definition at line 342 of file collision_common.h.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ fcl2costsource()

void collision_detection::fcl2costsource ( const fcl::CostSourced fcs,
CostSource cs 
)
inline

Transforms the FCL internal representation to the MoveIt CostSource data structure.

Definition at line 356 of file collision_common.h.

Here is the caller graph for this function:

◆ getAttachedBodyPointDecomposition()

PosedBodyPointDecompositionVectorPtr collision_detection::getAttachedBodyPointDecomposition ( const moveit::core::AttachedBody att,
double  resolution 
)

Definition at line 122 of file collision_common_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getAttachedBodySphereDecomposition()

PosedBodySphereDecompositionVectorPtr collision_detection::getAttachedBodySphereDecomposition ( const moveit::core::AttachedBody att,
double  resolution 
)

Definition at line 108 of file collision_common_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getBodyDecompositionCache()

BodyDecompositionCache& collision_detection::getBodyDecompositionCache ( )

Definition at line 64 of file collision_common_distance_field.cpp.

Here is the caller graph for this function:

◆ getBodyDecompositionCacheEntry()

BodyDecompositionConstPtr collision_detection::getBodyDecompositionCacheEntry ( const shapes::ShapeConstPtr &  shape,
double  resolution 
)

Definition at line 70 of file collision_common_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getBodySphereVisualizationMarkers() [1/2]

void collision_detection::getBodySphereVisualizationMarkers ( const GroupStateRepresentationConstPtr &  gsr,
const std::string &  reference_frame,
visualization_msgs::msg::MarkerArray &  body_marker_array 
)

Definition at line 136 of file collision_common_distance_field.cpp.

Here is the call graph for this function:

◆ getBodySphereVisualizationMarkers() [2/2]

void collision_detection::getBodySphereVisualizationMarkers ( const GroupStateRepresentationPtr &  gsr,
const std::string &  reference_frame,
visualization_msgs::msg::MarkerArray &  body_marker_array 
)

◆ getCollisionMarkers()

void collision_detection::getCollisionMarkers ( const std::string &  frame_id,
const std::string &  ns,
const rclcpp::Duration &  dur,
const std::vector< PosedBodySphereDecompositionPtr > &  posed_decompositions,
const std::vector< PosedBodySphereDecompositionVectorPtr > &  posed_vector_decompositions,
const std::vector< GradientInfo > &  gradients,
visualization_msgs::msg::MarkerArray &  arr 
)

Definition at line 545 of file collision_distance_field_types.cpp.

◆ getCollisionMarkersFromContacts() [1/2]

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

Definition at line 55 of file collision_tools.cpp.

Here is the call graph for this function:

◆ getCollisionMarkersFromContacts() [2/2]

void collision_detection::getCollisionMarkersFromContacts ( visualization_msgs::msg::MarkerArray &  arr,
const std::string &  frame_id,
const CollisionResult::ContactMap con,
const std_msgs::msg::ColorRGBA &  color,
const rclcpp::Duration &  lifetime,
const double  radius = 0.035 
)

Definition at line 98 of file collision_tools.cpp.

Here is the caller graph for this function:

◆ getCollisionObjectPointDecomposition()

PosedBodyPointDecompositionVectorPtr collision_detection::getCollisionObjectPointDecomposition ( const collision_detection::World::Object obj,
double  resolution 
)

Definition at line 94 of file collision_common_distance_field.cpp.

Here is the call graph for this function:

◆ getCollisionSphereCollision() [1/2]

bool collision_detection::getCollisionSphereCollision ( const distance_field::DistanceField distance_field,
const std::vector< CollisionSphere > &  sphere_list,
const EigenSTL::vector_Vector3d &  sphere_centers,
double  maximum_value,
double  tolerance 
)

Definition at line 205 of file collision_distance_field_types.cpp.

Here is the caller graph for this function:

◆ getCollisionSphereCollision() [2/2]

bool collision_detection::getCollisionSphereCollision ( const distance_field::DistanceField distance_field,
const std::vector< CollisionSphere > &  sphere_list,
const EigenSTL::vector_Vector3d &  sphere_centers,
double  maximum_value,
double  tolerance,
unsigned int  num_coll,
std::vector< unsigned int > &  colls 
)

Definition at line 232 of file collision_distance_field_types.cpp.

◆ getCollisionSphereGradients()

bool collision_detection::getCollisionSphereGradients ( const distance_field::DistanceField distance_field,
const std::vector< CollisionSphere > &  sphere_list,
const EigenSTL::vector_Vector3d &  sphere_centers,
GradientInfo gradient,
const CollisionType type,
double  tolerance,
bool  subtract_radii,
double  maximum_value,
bool  stop_at_first_collision 
)

Definition at line 144 of file collision_distance_field_types.cpp.

Here is the caller graph for this function:

◆ getCollisionSphereMarkers()

void collision_detection::getCollisionSphereMarkers ( const std_msgs::msg::ColorRGBA &  color,
const std::string &  frame_id,
const std::string &  ns,
const rclcpp::Duration &  dur,
const std::vector< PosedBodySphereDecompositionPtr > &  posed_decompositions,
visualization_msgs::msg::MarkerArray &  arr 
)

Definition at line 414 of file collision_distance_field_types.cpp.

◆ getCostMarkers() [1/2]

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

Definition at line 44 of file collision_tools.cpp.

◆ getCostMarkers() [2/2]

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

Definition at line 66 of file collision_tools.cpp.

◆ getProximityGradientMarkers()

void collision_detection::getProximityGradientMarkers ( const std::string &  frame_id,
const std::string &  ns,
const rclcpp::Duration &  dur,
const std::vector< PosedBodySphereDecompositionPtr > &  posed_decompositions,
const std::vector< PosedBodySphereDecompositionVectorPtr > &  posed_vector_decompositions,
const std::vector< GradientInfo > &  gradients,
visualization_msgs::msg::MarkerArray &  arr 
)

Definition at line 445 of file collision_distance_field_types.cpp.

◆ getSensorPositioning()

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

Definition at line 138 of file collision_tools.cpp.

◆ GetShapeCache()

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

Definition at line 671 of file collision_common.cpp.

◆ getTotalCost()

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

Definition at line 151 of file collision_tools.cpp.

◆ intersectCostSources()

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

Definition at line 159 of file collision_tools.cpp.

◆ MOVEIT_CLASS_FORWARD() [1/13]

collision_detection::MOVEIT_CLASS_FORWARD ( AllowedCollisionMatrix  )

◆ MOVEIT_CLASS_FORWARD() [2/13]

collision_detection::MOVEIT_CLASS_FORWARD ( BodyDecomposition  )

◆ MOVEIT_CLASS_FORWARD() [3/13]

collision_detection::MOVEIT_CLASS_FORWARD ( CollisionDetectorAllocator  )

◆ MOVEIT_CLASS_FORWARD() [4/13]

collision_detection::MOVEIT_CLASS_FORWARD ( CollisionEnv  )

◆ MOVEIT_CLASS_FORWARD() [5/13]

collision_detection::MOVEIT_CLASS_FORWARD ( CollisionEnvDistanceField  )

◆ MOVEIT_CLASS_FORWARD() [6/13]

collision_detection::MOVEIT_CLASS_FORWARD ( CollisionPlugin  )

◆ MOVEIT_CLASS_FORWARD() [7/13]

collision_detection::MOVEIT_CLASS_FORWARD ( PosedBodyPointDecomposition  )

◆ MOVEIT_CLASS_FORWARD() [8/13]

collision_detection::MOVEIT_CLASS_FORWARD ( PosedBodyPointDecompositionVector  )

◆ MOVEIT_CLASS_FORWARD() [9/13]

collision_detection::MOVEIT_CLASS_FORWARD ( PosedBodySphereDecomposition  )

◆ MOVEIT_CLASS_FORWARD() [10/13]

collision_detection::MOVEIT_CLASS_FORWARD ( PosedBodySphereDecompositionVector  )

◆ MOVEIT_CLASS_FORWARD() [11/13]

collision_detection::MOVEIT_CLASS_FORWARD ( PosedDistanceField  )

◆ MOVEIT_CLASS_FORWARD() [12/13]

collision_detection::MOVEIT_CLASS_FORWARD ( World  )

◆ MOVEIT_CLASS_FORWARD() [13/13]

collision_detection::MOVEIT_CLASS_FORWARD ( WorldDiff  )

◆ MOVEIT_STRUCT_FORWARD() [1/4]

collision_detection::MOVEIT_STRUCT_FORWARD ( CollisionGeometryData  )

◆ MOVEIT_STRUCT_FORWARD() [2/4]

collision_detection::MOVEIT_STRUCT_FORWARD ( DistanceFieldCacheEntry  )

◆ MOVEIT_STRUCT_FORWARD() [3/4]

collision_detection::MOVEIT_STRUCT_FORWARD ( FCLGeometry  )

◆ MOVEIT_STRUCT_FORWARD() [4/4]

collision_detection::MOVEIT_STRUCT_FORWARD ( GroupStateRepresentation  )

◆ refineContactNormals()

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 62 of file collision_octomap_filter.cpp.

◆ removeCostSources()

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

Definition at line 212 of file collision_tools.cpp.

Here is the caller graph for this function:

◆ removeOverlapping()

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

Definition at line 182 of file collision_tools.cpp.

Here is the caller graph for this function:

◆ transform2fcl() [1/2]

fcl::Transform3d collision_detection::transform2fcl ( const Eigen::Isometry3d &  b)
inline

Transforms an Eigen Isometry3d to FCL coordinate transformation.

Definition at line 334 of file collision_common.h.

Here is the call graph for this function:

◆ transform2fcl() [2/2]

void collision_detection::transform2fcl ( const Eigen::Isometry3d &  b,
fcl::Transform3d f 
)
inline

Transforms an Eigen Isometry3d to FCL coordinate transformation.

Definition at line 321 of file collision_common.h.

Here is the caller graph for this function:

Variable Documentation

◆ EPSILON

const double collision_detection::EPSILON = 0.001f

Definition at line 56 of file collision_env_distance_field.cpp.

◆ MAX_DISTANCE_MARGIN

const double collision_detection::MAX_DISTANCE_MARGIN = 99

Definition at line 50 of file collision_env_bullet.cpp.