moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Namespaces | Enumerations | Functions
collision_distance_field_types.h File Reference
#include <vector>
#include <string>
#include <algorithm>
#include <memory>
#include <float.h>
#include <geometric_shapes/shapes.h>
#include <geometric_shapes/bodies.h>
#include <octomap/OcTree.h>
#include <moveit/macros/class_forward.h>
#include <moveit/distance_field/distance_field.h>
#include <moveit/distance_field/propagation_distance_field.h>
#include <visualization_msgs/msg/marker_array.hpp>
#include <rclcpp/duration.hpp>
#include <rclcpp/logging.hpp>
#include <rclcpp/clock.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/time.hpp>
#include <rclcpp/utilities.hpp>
#include <moveit/utils/logger.hpp>
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

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

Namespaces

 collision_detection
 

Enumerations

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

Functions

 collision_detection::MOVEIT_CLASS_FORWARD (PosedDistanceField)
 
 collision_detection::MOVEIT_CLASS_FORWARD (BodyDecomposition)
 
 collision_detection::MOVEIT_CLASS_FORWARD (PosedBodySphereDecomposition)
 
 collision_detection::MOVEIT_CLASS_FORWARD (PosedBodyPointDecomposition)
 
 collision_detection::MOVEIT_CLASS_FORWARD (PosedBodySphereDecompositionVector)
 
 collision_detection::MOVEIT_CLASS_FORWARD (PosedBodyPointDecompositionVector)
 
std::vector< CollisionSphere > collision_detection::determineCollisionSpheres (const bodies::Body *body, Eigen::Isometry3d &relativeTransform)
 
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)
 
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::doBoundingSpheresIntersect (const PosedBodySphereDecompositionConstPtr &p1, const PosedBodySphereDecompositionConstPtr &p2)
 
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)
 
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)
 
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)