40#include <moveit_msgs/msg/cost_source.hpp>
41#include <moveit_msgs/msg/contact_information.hpp>
42#include <visualization_msgs/msg/marker_array.hpp>
44#include <rclcpp/rclcpp.hpp>
46#include <rclcpp/clock.hpp>
47#include <rclcpp/time.hpp>
53 const rclcpp::Duration& lifetime,
const double radius = 0.035);
59void getCostMarkers(visualization_msgs::msg::MarkerArray& arr,
const std::string& frame_id,
60 std::set<CostSource>& cost_sources);
62void getCostMarkers(visualization_msgs::msg::MarkerArray& arr,
const std::string& frame_id,
63 std::set<CostSource>& cost_sources,
const std_msgs::msg::ColorRGBA& color,
64 const rclcpp::Duration& lifetime);
66double getTotalCost(
const std::set<CostSource>& cost_sources);
68void removeCostSources(std::set<CostSource>& cost_sources,
const std::set<CostSource>& cost_sources_to_remove,
69 double overlap_fraction);
71 const std::set<CostSource>& b);
72void removeOverlapping(std::set<CostSource>& cost_sources,
double overlap_fraction);
74bool getSensorPositioning(geometry_msgs::msg::Point& point,
const std::set<CostSource>& cost_sources);
76void costSourceToMsg(
const CostSource& cost_source, moveit_msgs::msg::CostSource& msg);
77void contactToMsg(
const Contact& contact, moveit_msgs::msg::ContactInformation& msg);
bool getSensorPositioning(geometry_msgs::msg::Point &point, const std::set< CostSource > &cost_sources)
double getTotalCost(const std::set< CostSource > &cost_sources)
void getCollisionMarkersFromContacts(visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con, const std_msgs::msg::ColorRGBA &color, const rclcpp::Duration &lifetime, const double radius=0.035)
void getCostMarkers(visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources)
void intersectCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &a, const std::set< CostSource > &b)
void removeCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &cost_sources_to_remove, double overlap_fraction)
void contactToMsg(const Contact &contact, moveit_msgs::msg::ContactInformation &msg)
void removeOverlapping(std::set< CostSource > &cost_sources, double overlap_fraction)
void costSourceToMsg(const CostSource &cost_source, moveit_msgs::msg::CostSource &msg)
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
A map returning the pairs of body ids in contact, plus their contact details.