Classes | Namespaces | Typedefs | Enumerations | Functions
collision_distance_field_types.h File Reference
#include <vector>
#include <string>
#include <algorithm>
#include <sstream>
#include <float.h>
#include <geometric_shapes/shapes.h>
#include <geometric_shapes/bodies.h>
#include <octomap/OcTree.h>
#include <moveit/distance_field/distance_field.h>
#include <moveit/distance_field/propagation_distance_field.h>
#include <visualization_msgs/MarkerArray.h>
#include <console_bridge/console.h>
Include dependency graph for collision_distance_field_types.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  collision_detection::BodyDecomposition
struct  collision_detection::CollisionSphere
struct  collision_detection::GradientInfo
class  collision_detection::PosedBodyPointDecomposition
class  collision_detection::PosedBodyPointDecompositionVector
class  collision_detection::PosedBodySphereDecomposition
class  collision_detection::PosedBodySphereDecompositionVector
class  collision_detection::PosedDistanceField
struct  collision_detection::ProximityInfo

Namespaces

namespace  collision_detection

Typedefs

typedef boost::shared_ptr
< const BodyDecomposition > 
collision_detection::BodyDecompositionConstPtr
typedef boost::shared_ptr
< BodyDecomposition > 
collision_detection::BodyDecompositionPtr
typedef boost::shared_ptr
< const
PosedBodyPointDecomposition > 
collision_detection::PosedBodyPointDecompositionConstPtr
typedef boost::shared_ptr
< PosedBodyPointDecomposition > 
collision_detection::PosedBodyPointDecompositionPtr
typedef boost::shared_ptr
< const
PosedBodyPointDecompositionVector > 
collision_detection::PosedBodyPointDecompositionVectorConstPtr
typedef boost::shared_ptr
< PosedBodyPointDecompositionVector > 
collision_detection::PosedBodyPointDecompositionVectorPtr
typedef boost::shared_ptr
< const
PosedBodySphereDecomposition > 
collision_detection::PosedBodySphereDecompositionConstPtr
typedef boost::shared_ptr
< PosedBodySphereDecomposition > 
collision_detection::PosedBodySphereDecompositionPtr
typedef boost::shared_ptr
< const
PosedBodySphereDecompositionVector > 
collision_detection::PosedBodySphereDecompositionVectorConstPtr
typedef boost::shared_ptr
< PosedBodySphereDecompositionVector > 
collision_detection::PosedBodySphereDecompositionVectorPtr
typedef boost::shared_ptr
< const PosedDistanceField > 
collision_detection::PosedDistanceFieldConstPtr
typedef boost::shared_ptr
< PosedDistanceField > 
collision_detection::PosedDistanceFieldPtr

Enumerations

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

Functions

std::vector< CollisionSphere > collision_detection::determineCollisionSpheres (const bodies::Body *body, Eigen::Affine3d &relativeTransform)
bool collision_detection::doBoundingSpheresIntersect (const PosedBodySphereDecompositionConstPtr &p1, const PosedBodySphereDecompositionConstPtr &p2)
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)
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)
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)
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)
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)
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)


moveit_experimental
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley , Jorge Nicho
autogenerated on Wed Jun 19 2019 19:24:03