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 | AllowedCollisionMatrix |
| Definition of a structure for the allowed collision matrix. More... | |
| class | BodyDecomposition |
| struct | BodyDecompositionCache |
| struct | CollisionData |
| Data structure which is passed to the collision callback function of the collision manager. More... | |
| class | CollisionDetectorAllocator |
| An allocator for a compatible CollisionWorld/CollisionRobot pair. More... | |
| class | CollisionDetectorAllocatorAllValid |
| An allocator for AllValid collision detectors. More... | |
| class | CollisionDetectorAllocatorBullet |
| An allocator for Bullet collision detectors. More... | |
| class | CollisionDetectorAllocatorDistanceField |
| An allocator for Distance Field collision detectors. More... | |
| class | CollisionDetectorAllocatorFCL |
| An allocator for FCL collision detectors. More... | |
| class | CollisionDetectorAllocatorHybrid |
| An allocator for Hybrid collision detectors. More... | |
| class | CollisionDetectorAllocatorTemplate |
| Template class to make it easy to create an allocator for a specific CollisionWorld/CollisionRobot pair. More... | |
| class | CollisionDetectorBtPluginLoader |
| class | CollisionDetectorFCLPluginLoader |
| class | CollisionEnv |
| Provides the interface to the individual collision checking libraries. More... | |
| class | CollisionEnvAllValid |
| Collision environment which always just returns no collisions. More... | |
| class | CollisionEnvBullet |
More... | |
| class | CollisionEnvDistanceField |
| class | CollisionEnvFCL |
| FCL implementation of the CollisionEnv. More... | |
| class | CollisionEnvHybrid |
| This hybrid collision environment combines FCL and a distance field. Both can be used to calculate collisions. More... | |
| struct | CollisionGeometryData |
| Wrapper around world, link and attached objects' geometry data. More... | |
| class | CollisionPlugin |
| Plugin API for loading a custom collision detection robot/world. More... | |
| class | CollisionPluginCache |
| struct | CollisionRequest |
| Representation of a collision checking request. More... | |
| struct | CollisionResult |
| Representation of a collision checking result. More... | |
| struct | CollisionSphere |
| 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 | DistanceData |
| Data structure which is passed to the distance callback function of the collision manager. More... | |
| struct | DistanceFieldCacheEntry |
| struct | DistanceRequest |
| Representation of a distance-reporting request. More... | |
| struct | DistanceResult |
| Result of a distance request. More... | |
| struct | DistanceResultsData |
| Generic representation of the distance information for a pair of objects. More... | |
| struct | FCLGeometry |
| Bundles the CollisionGeometryData and FCL collision geometry representation into a single class. More... | |
| struct | FCLManager |
| Bundles an FCLObject and a broadphase FCL collision manager. 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 | FCLShapeCache |
| Cache for an arbitrary type of shape. It is assigned during the execution of createCollisionGeometry(). More... | |
| struct | GradientInfo |
| struct | GroupStateRepresentation |
| class | OccMapTree |
| class | PosedBodyPointDecomposition |
| class | PosedBodyPointDecompositionVector |
| class | PosedBodySphereDecomposition |
| class | PosedBodySphereDecompositionVector |
| class | PosedDistanceField |
| struct | ProximityInfo |
| 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 | |
| using | BodyType = BodyTypes::Type |
| The types of bodies that are considered for collision. More... | |
| using | DecideContactFn = boost::function< bool(collision_detection::Contact &)> |
| Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type is CONDITIONAL) More... | |
| 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 | DistanceRequestType = DistanceRequestTypes::DistanceRequestType |
| typedef std::shared_ptr< const fcl::CollisionObjectd > | FCLCollisionObjectConstPtr |
| typedef std::shared_ptr< fcl::CollisionObjectd > | FCLCollisionObjectPtr |
| typedef octomap::OcTreeNode | OccMapNode |
| using | OccMapTreeConstPtr = std::shared_ptr< const OccMapTree > |
| using | OccMapTreePtr = std::shared_ptr< OccMapTree > |
Enumerations | |
| enum | CollisionType { NONE = 0, SELF = 1, INTRA = 2, ENVIRONMENT = 3 } |
Functions | |
| static bool | andDecideContact (const DecideContactFn &f1, const DecideContactFn &f2, Contact &contact) |
| void | cleanCollisionGeometryCache () |
| Increases the counter of the caches which can trigger the cleaning of expired entries from them. More... | |
| 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... | |
| 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 moveit::core::AttachedBody *ab, int shape_index) |
| Create new FCLGeometry object out of attached body. 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... | |
| 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... | |
| 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::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 moveit::core::LinkModel *link, int shape_index) |
| Create new scaled and / or padded FCLGeometry object out of robot link model. 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... | |
| 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... | |
| std::vector< CollisionSphere > | determineCollisionSpheres (const bodies::Body *body, Eigen::Isometry3d &relativeTransform) |
| 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... | |
| bool | doBoundingSpheresIntersect (const PosedBodySphereDecompositionConstPtr &p1, const PosedBodySphereDecompositionConstPtr &p2) |
| 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... | |
| PosedBodyPointDecompositionVectorPtr | getAttachedBodyPointDecomposition (const moveit::core::AttachedBody *att, double resolution) |
| PosedBodySphereDecompositionVectorPtr | getAttachedBodySphereDecomposition (const moveit::core::AttachedBody *att, double resolution) |
| BodyDecompositionCache & | getBodyDecompositionCache () |
| BodyDecompositionConstPtr | getBodyDecompositionCacheEntry (const shapes::ShapeConstPtr &shape, double resolution) |
| void | getBodySphereVisualizationMarkers (const GroupStateRepresentationConstPtr &gsr, const std::string &reference_frame, visualization_msgs::MarkerArray &body_marker_array) |
| void | getBodySphereVisualizationMarkers (const GroupStateRepresentationPtr &gsr, const std::string &reference_frame, visualization_msgs::MarkerArray &body_marker_array) |
| void | getCollisionMarkers (const std::string &frame_id, const std::string &ns, const ros::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, const std::vector< PosedBodySphereDecompositionVectorPtr > &posed_vector_decompositions, const std::vector< GradientInfo > &gradients, visualization_msgs::MarkerArray &arr) |
| void | getCollisionMarkersFromContacts (visualization_msgs::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con) |
| 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) |
| PosedBodyPointDecompositionVectorPtr | getCollisionObjectPointDecomposition (const collision_detection::World::Object &obj, double resolution) |
| 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 | 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) |
| void | getCollisionSphereMarkers (const std_msgs::ColorRGBA &color, const std::string &frame_id, const std::string &ns, const ros::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, visualization_msgs::MarkerArray &arr) |
| 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) |
| void | getProximityGradientMarkers (const std::string &frame_id, const std::string &ns, const ros::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, const std::vector< PosedBodySphereDecompositionVectorPtr > &posed_vector_decompositions, const std::vector< GradientInfo > &gradients, visualization_msgs::MarkerArray &arr) |
| bool | getSensorPositioning (geometry_msgs::Point &point, const std::set< CostSource > &cost_sources) |
| template<typename BV , typename T > | |
| FCLShapeCache & | GetShapeCache () |
| 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) |
| MOVEIT_CLASS_FORWARD (AllowedCollisionMatrix) | |
| MOVEIT_CLASS_FORWARD (BodyDecomposition) | |
| MOVEIT_CLASS_FORWARD (CollisionDetectorAllocator) | |
| MOVEIT_CLASS_FORWARD (CollisionEnv) | |
| MOVEIT_CLASS_FORWARD (CollisionEnvDistanceField) | |
| MOVEIT_CLASS_FORWARD (CollisionPlugin) | |
| MOVEIT_CLASS_FORWARD (PosedBodyPointDecomposition) | |
| MOVEIT_CLASS_FORWARD (PosedBodyPointDecompositionVector) | |
| MOVEIT_CLASS_FORWARD (PosedBodySphereDecomposition) | |
| MOVEIT_CLASS_FORWARD (PosedBodySphereDecompositionVector) | |
| MOVEIT_CLASS_FORWARD (PosedDistanceField) | |
| MOVEIT_CLASS_FORWARD (World) | |
| MOVEIT_CLASS_FORWARD (WorldDiff) | |
| MOVEIT_STRUCT_FORWARD (CollisionGeometryData) | |
| MOVEIT_STRUCT_FORWARD (DistanceFieldCacheEntry) | |
| MOVEIT_STRUCT_FORWARD (FCLGeometry) | |
| MOVEIT_STRUCT_FORWARD (GroupStateRepresentation) | |
| 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... | |
| 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) |
| fcl::Transform3d | transform2fcl (const Eigen::Isometry3d &b) |
| Transforms an Eigen Isometry3d to FCL coordinate transformation. More... | |
| void | transform2fcl (const Eigen::Isometry3d &b, fcl::Transform3d &f) |
| Transforms an Eigen Isometry3d to FCL coordinate transformation. More... | |
Variables | |
| static const double | DEFAULT_COLLISION_TOLERANCE = 0.0 |
| static const double | DEFAULT_MAX_PROPOGATION_DISTANCE = .25 |
| static const double | DEFAULT_RESOLUTION = .02 |
| static const double | DEFAULT_SIZE_X = 3.0 |
| static const double | DEFAULT_SIZE_Y = 3.0 |
| static const double | DEFAULT_SIZE_Z = 4.0 |
| static const bool | DEFAULT_USE_SIGNED_DISTANCE_FIELD = false |
| constexpr char | LOGNAME [] = "collision_detection.fcl" |
| static const std::string | NAME = "FCL" |
| using collision_detection::BodyType = typedef BodyTypes::Type |
The types of bodies that are considered for collision.
Definition at line 102 of file include/moveit/collision_detection/collision_common.h.
| using collision_detection::DecideContactFn = typedef boost::function<bool(collision_detection::Contact&)> |
Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type is CONDITIONAL)
Definition at line 104 of file collision_matrix.h.
| 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 354 of file include/moveit/collision_detection/collision_common.h.
Definition at line 238 of file include/moveit/collision_detection/collision_common.h.
| typedef std::shared_ptr<const fcl::CollisionObjectd> collision_detection::FCLCollisionObjectConstPtr |
Definition at line 280 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
| typedef std::shared_ptr<fcl::CollisionObjectd> collision_detection::FCLCollisionObjectPtr |
Definition at line 279 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
Definition at line 79 of file occupancy_map.h.
| using collision_detection::OccMapTreeConstPtr = typedef std::shared_ptr<const OccMapTree> |
Definition at line 149 of file occupancy_map.h.
| using collision_detection::OccMapTreePtr = typedef std::shared_ptr<OccMapTree> |
Definition at line 148 of file occupancy_map.h.
| Enumerator | |
|---|---|
| NONE | |
| SELF | |
| INTRA | |
| ENVIRONMENT | |
Definition at line 89 of file collision_distance_field_types.h.
|
static |
Definition at line 307 of file collision_matrix.cpp.
| void collision_detection::cleanCollisionGeometryCache | ( | ) |
Increases the counter of the caches which can trigger the cleaning of expired entries from them.
Definition at line 958 of file fcl/src/collision_common.cpp.
| 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.
| o1 | First FCL collision object |
| o2 | Second FCL collision object |
| data | General pointer to arbitrary data which is used during the callback |
Definition at line 88 of file fcl/src/collision_common.cpp.
| void collision_detection::contactToMsg | ( | const Contact & | contact, |
| moveit_msgs::ContactInformation & | msg | ||
| ) |
Definition at line 304 of file collision_tools.cpp.
| void collision_detection::costSourceToMsg | ( | const CostSource & | cost_source, |
| moveit_msgs::CostSource & | msg | ||
| ) |
Definition at line 293 of file collision_tools.cpp.
| 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 912 of file fcl/src/collision_common.cpp.
| 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 906 of file fcl/src/collision_common.cpp.
| 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 727 of file fcl/src/collision_common.cpp.
| 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 918 of file fcl/src/collision_common.cpp.
| 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 946 of file fcl/src/collision_common.cpp.
| 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 940 of file fcl/src/collision_common.cpp.
| 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 926 of file fcl/src/collision_common.cpp.
| 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 952 of file fcl/src/collision_common.cpp.
| std::vector< collision_detection::CollisionSphere > collision_detection::determineCollisionSpheres | ( | const bodies::Body * | body, |
| Eigen::Isometry3d & | relativeTransform | ||
| ) |
Definition at line 47 of file collision_distance_field_types.cpp.
| 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.
| o1 | First FCL collision object |
| o2 | Second FCL collision object |
| data | General pointer to arbitrary data which is used during the callback |
Definition at line 443 of file fcl/src/collision_common.cpp.
| bool collision_detection::doBoundingSpheresIntersect | ( | const PosedBodySphereDecompositionConstPtr & | p1, |
| const PosedBodySphereDecompositionConstPtr & | p2 | ||
| ) |
Definition at line 410 of file collision_distance_field_types.cpp.
|
inline |
Transforms an FCL contact into a MoveIt contact point.
Definition at line 371 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
|
inline |
Transforms the FCL internal representation to the MoveIt CostSource data structure.
Definition at line 385 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
| PosedBodyPointDecompositionVectorPtr collision_detection::getAttachedBodyPointDecomposition | ( | const moveit::core::AttachedBody * | att, |
| double | resolution | ||
| ) |
Definition at line 149 of file collision_common_distance_field.cpp.
| PosedBodySphereDecompositionVectorPtr collision_detection::getAttachedBodySphereDecomposition | ( | const moveit::core::AttachedBody * | att, |
| double | resolution | ||
| ) |
Definition at line 135 of file collision_common_distance_field.cpp.
| BodyDecompositionCache& collision_detection::getBodyDecompositionCache | ( | ) |
Definition at line 91 of file collision_common_distance_field.cpp.
| BodyDecompositionConstPtr collision_detection::getBodyDecompositionCacheEntry | ( | const shapes::ShapeConstPtr & | shape, |
| double | resolution | ||
| ) |
Definition at line 97 of file collision_common_distance_field.cpp.
| void collision_detection::getBodySphereVisualizationMarkers | ( | const GroupStateRepresentationConstPtr & | gsr, |
| const std::string & | reference_frame, | ||
| visualization_msgs::MarkerArray & | body_marker_array | ||
| ) |
Definition at line 163 of file collision_common_distance_field.cpp.
| void collision_detection::getBodySphereVisualizationMarkers | ( | const GroupStateRepresentationPtr & | gsr, |
| const std::string & | reference_frame, | ||
| visualization_msgs::MarkerArray & | body_marker_array | ||
| ) |
| void collision_detection::getCollisionMarkers | ( | const std::string & | frame_id, |
| const std::string & | ns, | ||
| const ros::Duration & | dur, | ||
| const std::vector< PosedBodySphereDecompositionPtr > & | posed_decompositions, | ||
| const std::vector< PosedBodySphereDecompositionVectorPtr > & | posed_vector_decompositions, | ||
| const std::vector< GradientInfo > & | gradients, | ||
| visualization_msgs::MarkerArray & | arr | ||
| ) |
Definition at line 554 of file collision_distance_field_types.cpp.
| void collision_detection::getCollisionMarkersFromContacts | ( | visualization_msgs::MarkerArray & | arr, |
| const std::string & | frame_id, | ||
| const CollisionResult::ContactMap & | con | ||
| ) |
Definition at line 85 of file collision_tools.cpp.
| 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 127 of file collision_tools.cpp.
| PosedBodyPointDecompositionVectorPtr collision_detection::getCollisionObjectPointDecomposition | ( | const collision_detection::World::Object & | obj, |
| double | resolution | ||
| ) |
Definition at line 121 of file collision_common_distance_field.cpp.
| 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 206 of file collision_distance_field_types.cpp.
| 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 233 of file collision_distance_field_types.cpp.
| 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 143 of file collision_distance_field_types.cpp.
| void collision_detection::getCollisionSphereMarkers | ( | const std_msgs::ColorRGBA & | color, |
| const std::string & | frame_id, | ||
| const std::string & | ns, | ||
| const ros::Duration & | dur, | ||
| const std::vector< PosedBodySphereDecompositionPtr > & | posed_decompositions, | ||
| visualization_msgs::MarkerArray & | arr | ||
| ) |
Definition at line 422 of file collision_distance_field_types.cpp.
| void collision_detection::getCostMarkers | ( | visualization_msgs::MarkerArray & | arr, |
| const std::string & | frame_id, | ||
| std::set< CostSource > & | cost_sources | ||
| ) |
Definition at line 74 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 96 of file collision_tools.cpp.
| void collision_detection::getProximityGradientMarkers | ( | const std::string & | frame_id, |
| const std::string & | ns, | ||
| const ros::Duration & | dur, | ||
| const std::vector< PosedBodySphereDecompositionPtr > & | posed_decompositions, | ||
| const std::vector< PosedBodySphereDecompositionVectorPtr > & | posed_vector_decompositions, | ||
| const std::vector< GradientInfo > & | gradients, | ||
| visualization_msgs::MarkerArray & | arr | ||
| ) |
Definition at line 451 of file collision_distance_field_types.cpp.
| bool collision_detection::getSensorPositioning | ( | geometry_msgs::Point & | point, |
| const std::set< CostSource > & | cost_sources | ||
| ) |
Definition at line 166 of file collision_tools.cpp.
| FCLShapeCache& collision_detection::GetShapeCache | ( | ) |
Definition at line 706 of file fcl/src/collision_common.cpp.
| double collision_detection::getTotalCost | ( | const std::set< CostSource > & | cost_sources | ) |
Definition at line 179 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 187 of file collision_tools.cpp.
| collision_detection::MOVEIT_CLASS_FORWARD | ( | AllowedCollisionMatrix | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | BodyDecomposition | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | CollisionDetectorAllocator | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | CollisionEnv | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | CollisionEnvDistanceField | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | CollisionPlugin | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | PosedBodyPointDecomposition | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | PosedBodyPointDecompositionVector | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | PosedBodySphereDecomposition | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | PosedBodySphereDecompositionVector | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | PosedDistanceField | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | World | ) |
| collision_detection::MOVEIT_CLASS_FORWARD | ( | WorldDiff | ) |
| collision_detection::MOVEIT_STRUCT_FORWARD | ( | CollisionGeometryData | ) |
| collision_detection::MOVEIT_STRUCT_FORWARD | ( | DistanceFieldCacheEntry | ) |
| collision_detection::MOVEIT_STRUCT_FORWARD | ( | FCLGeometry | ) |
| collision_detection::MOVEIT_STRUCT_FORWARD | ( | GroupStateRepresentation | ) |
| 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
| object | The octomap originally used for collision detection. |
| res | The collision result (which will get its normals updated) |
| cell_bbx_search_distance | The distance, as a multiple of the octomap cell size, from which to include neighboring cells. |
| allowed_angle_divergence | The minimum angle change required for a normal to be over-written |
| estimate_depth | Whether to request a depth estimate from the algorithm (experimental...) |
| iso_value | The iso-surface threshold value (0.5 is a reasonable default). |
| metaball_radius_multiple | The metaball radius, as a multiple of the octomap cell size (1.5 is a reasonable default) |
Definition at line 60 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 240 of file collision_tools.cpp.
| void collision_detection::removeOverlapping | ( | std::set< CostSource > & | cost_sources, |
| double | overlap_fraction | ||
| ) |
Definition at line 210 of file collision_tools.cpp.
|
inline |
Transforms an Eigen Isometry3d to FCL coordinate transformation.
Definition at line 363 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
|
inline |
Transforms an Eigen Isometry3d to FCL coordinate transformation.
Definition at line 350 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
|
static |
Definition at line 85 of file collision_env_distance_field.h.
|
static |
Definition at line 86 of file collision_env_distance_field.h.
|
static |
Definition at line 84 of file collision_env_distance_field.h.
|
static |
Definition at line 80 of file collision_env_distance_field.h.
|
static |
Definition at line 81 of file collision_env_distance_field.h.
|
static |
Definition at line 82 of file collision_env_distance_field.h.
|
static |
Definition at line 83 of file collision_env_distance_field.h.
|
constexpr |
Definition at line 82 of file collision_env_fcl.cpp.
|
static |
Definition at line 81 of file collision_env_fcl.cpp.