40 #include <moveit_msgs/CostSource.h>
41 #include <moveit_msgs/ContactInformation.h>
42 #include <visualization_msgs/MarkerArray.h>
54 void getCostMarkers(visualization_msgs::MarkerArray& arr,
const std::string& frame_id,
55 std::set<CostSource>& cost_sources);
57 void getCostMarkers(visualization_msgs::MarkerArray& arr,
const std::string& frame_id,
58 std::set<CostSource>& cost_sources,
const std_msgs::ColorRGBA& color,
61 double getTotalCost(
const std::set<CostSource>& cost_sources);
63 void removeCostSources(std::set<CostSource>& cost_sources,
const std::set<CostSource>& cost_sources_to_remove,
64 double overlap_fraction);
66 const std::set<CostSource>& b);
67 void removeOverlapping(std::set<CostSource>& cost_sources,
double overlap_fraction);
71 void costSourceToMsg(
const CostSource& cost_source, moveit_msgs::CostSource& msg);
72 void contactToMsg(
const Contact& contact, moveit_msgs::ContactInformation& msg);