Generic interface to collision detection. More...
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. 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 | 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 | 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 | CollisionDetectorFCLPluginLoader |
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... | |
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 | CollisionRobotDistanceField |
class | CollisionRobotFCL |
class | CollisionRobotHybrid |
struct | CollisionSphere |
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 | CollisionWorldDistanceField |
class | CollisionWorldFCL |
class | CollisionWorldHybrid |
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 |
struct | IfSameType |
struct | IfSameType< T, T > |
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 | |
typedef BodyTypes::Type | BodyType |
The types of bodies that are considered for collision. More... | |
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) More... | |
typedef std::map< const std::pair< std::string, std::string >, std::vector< DistanceResultsData > > | DistanceMap |
Mapping between the names of the collision objects and the DistanceResultData. More... | |
typedef DistanceRequestTypes::DistanceRequestType | DistanceRequestType |
typedef std::shared_ptr< const fcl::CollisionObjectd > | FCLCollisionObjectConstPtr |
typedef std::shared_ptr< fcl::CollisionObjectd > | FCLCollisionObjectPtr |
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 robot_model::LinkModel *link, int shape_index) |
Create new FCLGeometry object out of robot link model. More... | |
FCLGeometryConstPtr | createCollisionGeometry (const shapes::ShapeConstPtr &shape, const robot_state::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 robot_model::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 robot_state::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... | |
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... | |
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 robot_state::AttachedBody *att, double resolution) |
PosedBodySphereDecompositionVectorPtr | getAttachedBodySphereDecomposition (const robot_state::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, 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) |
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 (CollisionPlugin) | |
MOVEIT_CLASS_FORWARD (WorldDiff) | |
MOVEIT_CLASS_FORWARD (CollisionDetectorAllocator) | |
MOVEIT_CLASS_FORWARD (CollisionRobot) | |
MOVEIT_CLASS_FORWARD (CollisionWorld) | |
MOVEIT_CLASS_FORWARD (AllowedCollisionMatrix) | |
MOVEIT_CLASS_FORWARD (World) | |
MOVEIT_CLASS_FORWARD (CollisionRobotDistanceField) | |
MOVEIT_CLASS_FORWARD (BodyDecomposition) | |
MOVEIT_STRUCT_FORWARD (CollisionGeometryData) | |
MOVEIT_STRUCT_FORWARD (FCLGeometry) | |
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) |
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... | |
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 |
const double | EPSILON = 0.001f |
constexpr char | LOGNAME [] = "collision_detection.bullet" |
const double | MAX_DISTANCE_MARGIN = 99 |
Generic interface to collision detection.
The types of bodies that are considered for collision.
Definition at line 71 of file include/moveit/collision_detection/collision_common.h.
typedef boost::function<bool(collision_detection::Contact&)> collision_detection::DecideContactFn |
Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type is CONDITIONAL)
Definition at line 73 of file collision_matrix.h.
typedef std::map<const std::pair<std::string, std::string>, std::vector<DistanceResultsData> > collision_detection::DistanceMap |
Mapping between the names of the collision objects and the DistanceResultData.
Definition at line 351 of file include/moveit/collision_detection/collision_common.h.
Definition at line 235 of file include/moveit/collision_detection/collision_common.h.
typedef std::shared_ptr<const fcl::CollisionObjectd> collision_detection::FCLCollisionObjectConstPtr |
Definition at line 247 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
typedef std::shared_ptr<fcl::CollisionObjectd> collision_detection::FCLCollisionObjectPtr |
Definition at line 246 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
Enumerator | |
---|---|
NONE | |
SELF | |
INTRA | |
ENVIRONMENT |
Definition at line 58 of file collision_distance_field_types.h.
|
static |
Definition at line 250 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 922 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 General pointer to arbitrary data which is used during the callback |
Definition at line 55 of file fcl/src/collision_common.cpp.
void collision_detection::contactToMsg | ( | const Contact & | contact, |
moveit_msgs::ContactInformation & | msg | ||
) |
Definition at line 272 of file collision_tools.cpp.
void collision_detection::costSourceToMsg | ( | const CostSource & | cost_source, |
moveit_msgs::CostSource & | msg | ||
) |
Definition at line 261 of file collision_tools.cpp.
FCLGeometryConstPtr collision_detection::createCollisionGeometry | ( | const shapes::ShapeConstPtr & | shape, |
const robot_model::LinkModel * | link, | ||
int | shape_index | ||
) |
Create new FCLGeometry object out of robot link model.
Definition at line 870 of file fcl/src/collision_common.cpp.
FCLGeometryConstPtr collision_detection::createCollisionGeometry | ( | const shapes::ShapeConstPtr & | shape, |
const robot_state::AttachedBody * | ab, | ||
int | shape_index | ||
) |
Create new FCLGeometry object out of attached body.
Definition at line 876 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 882 of file fcl/src/collision_common.cpp.
FCLGeometryConstPtr collision_detection::createCollisionGeometry | ( | const shapes::ShapeConstPtr & | shape, |
double | scale, | ||
double | padding, | ||
const robot_model::LinkModel * | link, | ||
int | shape_index | ||
) |
Create new scaled and / or padded FCLGeometry object out of robot link model.
Definition at line 904 of file fcl/src/collision_common.cpp.
FCLGeometryConstPtr collision_detection::createCollisionGeometry | ( | const shapes::ShapeConstPtr & | shape, |
double | scale, | ||
double | padding, | ||
const robot_state::AttachedBody * | ab, | ||
int | shape_index | ||
) |
Create new scaled and / or padded FCLGeometry object out of an attached body.
Definition at line 910 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 916 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 691 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 890 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 General pointer to arbitrary data which is used during the callback |
Definition at line 410 of file fcl/src/collision_common.cpp.
bool collision_detection::doBoundingSpheresIntersect | ( | const PosedBodySphereDecompositionConstPtr & | p1, |
const PosedBodySphereDecompositionConstPtr & | p2 | ||
) |
Definition at line 396 of file collision_distance_field_types.cpp.
|
inline |
Transforms an FCL contact into a MoveIt contact point.
Definition at line 337 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 351 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
PosedBodyPointDecompositionVectorPtr collision_detection::getAttachedBodyPointDecomposition | ( | const robot_state::AttachedBody * | att, |
double | resolution | ||
) |
Definition at line 117 of file collision_common_distance_field.cpp.
PosedBodySphereDecompositionVectorPtr collision_detection::getAttachedBodySphereDecomposition | ( | const robot_state::AttachedBody * | att, |
double | resolution | ||
) |
Definition at line 103 of file collision_common_distance_field.cpp.
BodyDecompositionCache& collision_detection::getBodyDecompositionCache | ( | ) |
Definition at line 59 of file collision_common_distance_field.cpp.
BodyDecompositionConstPtr collision_detection::getBodyDecompositionCacheEntry | ( | const shapes::ShapeConstPtr & | shape, |
double | resolution | ||
) |
Definition at line 65 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 131 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 541 of file collision_distance_field_types.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 95 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 53 of file collision_tools.cpp.
PosedBodyPointDecompositionVectorPtr collision_detection::getCollisionObjectPointDecomposition | ( | const collision_detection::World::Object & | obj, |
double | resolution | ||
) |
Definition at line 89 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 192 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 219 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 129 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 408 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 42 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 64 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 438 of file collision_distance_field_types.cpp.
bool collision_detection::getSensorPositioning | ( | geometry_msgs::Point & | point, |
const std::set< CostSource > & | cost_sources | ||
) |
Definition at line 134 of file collision_tools.cpp.
FCLShapeCache& collision_detection::GetShapeCache | ( | ) |
Definition at line 652 of file fcl/src/collision_common.cpp.
double collision_detection::getTotalCost | ( | const std::set< CostSource > & | cost_sources | ) |
Definition at line 147 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.
collision_detection::MOVEIT_CLASS_FORWARD | ( | CollisionPlugin | ) |
collision_detection::MOVEIT_CLASS_FORWARD | ( | WorldDiff | ) |
collision_detection::MOVEIT_CLASS_FORWARD | ( | CollisionDetectorAllocator | ) |
collision_detection::MOVEIT_CLASS_FORWARD | ( | CollisionRobot | ) |
collision_detection::MOVEIT_CLASS_FORWARD | ( | CollisionWorld | ) |
collision_detection::MOVEIT_CLASS_FORWARD | ( | AllowedCollisionMatrix | ) |
collision_detection::MOVEIT_CLASS_FORWARD | ( | World | ) |
collision_detection::MOVEIT_CLASS_FORWARD | ( | CollisionRobotDistanceField | ) |
collision_detection::MOVEIT_CLASS_FORWARD | ( | BodyDecomposition | ) |
collision_detection::MOVEIT_STRUCT_FORWARD | ( | CollisionGeometryData | ) |
collision_detection::MOVEIT_STRUCT_FORWARD | ( | FCLGeometry | ) |
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
The | octomap originally used for collision detection. |
The | collision result (which will get its normals updated) |
The | distance, as a multiple of the octomap cell size, from which to include neighboring cells. |
The | minimum angle change required for a normal to be over-written |
Whether | to request a depth estimate from the algorithm (experimental...) |
The | iso-surface threshold value (0.5 is a reasonable default). |
The | metaball radius, as a multiple of the octomap cell size (1.5 is a reasonable default) |
Definition at line 61 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 178 of file collision_tools.cpp.
|
inline |
Transforms an Eigen Isometry3d to FCL coordinate transformation.
Definition at line 317 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
|
inline |
Transforms an Eigen Isometry3d to FCL coordinate transformation.
Definition at line 329 of file fcl/include/moveit/collision_detection_fcl/collision_common.h.
|
static |
Definition at line 54 of file collision_robot_distance_field.h.
|
static |
Definition at line 55 of file collision_robot_distance_field.h.
|
static |
Definition at line 53 of file collision_robot_distance_field.h.
|
static |
Definition at line 49 of file collision_robot_distance_field.h.
|
static |
Definition at line 50 of file collision_robot_distance_field.h.
|
static |
Definition at line 51 of file collision_robot_distance_field.h.
|
static |
Definition at line 52 of file collision_robot_distance_field.h.
const double collision_detection::EPSILON = 0.001f |
Definition at line 47 of file collision_robot_distance_field.cpp.
constexpr char collision_detection::LOGNAME[] = "collision_detection.bullet" |
Definition at line 48 of file collision_env_bullet.cpp.
const double collision_detection::MAX_DISTANCE_MARGIN = 99 |
Definition at line 47 of file collision_env_bullet.cpp.