37 #ifndef MOVEIT_COLLISION_DETECTION_COLLISION_TOOLS_ 38 #define MOVEIT_COLLISION_DETECTION_COLLISION_TOOLS_ 41 #include <moveit_msgs/CostSource.h> 42 #include <moveit_msgs/ContactInformation.h> 43 #include <visualization_msgs/MarkerArray.h> 55 void getCostMarkers(visualization_msgs::MarkerArray& arr,
const std::string& frame_id,
56 std::set<CostSource>& cost_sources);
58 void getCostMarkers(visualization_msgs::MarkerArray& arr,
const std::string& frame_id,
59 std::set<CostSource>& cost_sources,
const std_msgs::ColorRGBA& color,
62 double getTotalCost(
const std::set<CostSource>& cost_sources);
64 void removeCostSources(std::set<CostSource>& cost_sources,
const std::set<CostSource>& cost_sources_to_remove,
65 double overlap_fraction);
67 const std::set<CostSource>& b);
68 void removeOverlapping(std::set<CostSource>& cost_sources,
double overlap_fraction);
70 bool getSensorPositioning(geometry_msgs::Point& point,
const std::set<CostSource>& cost_sources);
72 void costSourceToMsg(
const CostSource& cost_source, moveit_msgs::CostSource& msg);
73 void contactToMsg(
const Contact& contact, moveit_msgs::ContactInformation& msg);
void getCostMarkers(visualization_msgs::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources)
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)
double getTotalCost(const std::set< CostSource > &cost_sources)
void costSourceToMsg(const CostSource &cost_source, moveit_msgs::CostSource &msg)
void contactToMsg(const Contact &contact, moveit_msgs::ContactInformation &msg)
Generic interface to collision detection.
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
void intersectCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &a, const std::set< CostSource > &b)
bool getSensorPositioning(geometry_msgs::Point &point, const std::set< CostSource > &cost_sources)
void removeOverlapping(std::set< CostSource > &cost_sources, double overlap_fraction)
void removeCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &cost_sources_to_remove, double overlap_fraction)