42 void getCostMarkers(visualization_msgs::MarkerArray& arr,
const std::string& frame_id,
43 std::set<CostSource>& cost_sources)
45 std_msgs::ColorRGBA color;
56 std_msgs::ColorRGBA color;
64 void getCostMarkers(visualization_msgs::MarkerArray& arr,
const std::string& frame_id,
65 std::set<CostSource>& cost_sources,
const std_msgs::ColorRGBA& color,
const ros::Duration& lifetime)
68 for (
const auto& cost_source : cost_sources)
70 visualization_msgs::Marker mk;
72 mk.header.frame_id = frame_id;
73 mk.ns =
"cost_source";
75 mk.type = visualization_msgs::Marker::CUBE;
76 mk.action = visualization_msgs::Marker::ADD;
77 mk.pose.position.x = (cost_source.aabb_max[0] + cost_source.aabb_min[0]) / 2.0;
78 mk.pose.position.y = (cost_source.aabb_max[1] + cost_source.aabb_min[1]) / 2.0;
79 mk.pose.position.z = (cost_source.aabb_max[2] + cost_source.aabb_min[2]) / 2.0;
80 mk.pose.orientation.x = 0.0;
81 mk.pose.orientation.y = 0.0;
82 mk.pose.orientation.z = 0.0;
83 mk.pose.orientation.w = 1.0;
84 mk.scale.x = cost_source.aabb_max[0] - cost_source.aabb_min[0];
85 mk.scale.y = cost_source.aabb_max[1] - cost_source.aabb_min[1];
86 mk.scale.z = cost_source.aabb_max[2] - cost_source.aabb_min[2];
88 if (mk.color.a == 0.0)
90 mk.lifetime = lifetime;
91 arr.markers.push_back(mk);
100 std::map<std::string, unsigned> ns_counts;
101 for (
const auto& collision : con)
103 for (
const auto& contact : collision.second)
105 std::string ns_name = contact.body_name_1 +
"=" + contact.body_name_2;
106 if (ns_counts.find(ns_name) == ns_counts.end())
107 ns_counts[ns_name] = 0;
109 ns_counts[ns_name]++;
110 visualization_msgs::Marker mk;
112 mk.header.frame_id = frame_id;
114 mk.id = ns_counts[ns_name];
115 mk.type = visualization_msgs::Marker::SPHERE;
116 mk.action = visualization_msgs::Marker::ADD;
117 mk.pose.position.x = contact.pos.x();
118 mk.pose.position.y = contact.pos.y();
119 mk.pose.position.z = contact.pos.z();
120 mk.pose.orientation.x = 0.0;
121 mk.pose.orientation.y = 0.0;
122 mk.pose.orientation.z = 0.0;
123 mk.pose.orientation.w = 1.0;
124 mk.scale.x = mk.scale.y = mk.scale.z = radius * 2.0;
126 if (mk.color.a == 0.0)
128 mk.lifetime = lifetime;
129 arr.markers.push_back(mk);
136 if (cost_sources.empty())
138 auto it = cost_sources.begin();
139 for (std::size_t i = 0; i < 4 * cost_sources.size() / 5; ++i)
141 point.x = (it->aabb_max[0] + it->aabb_min[0]) / 2.0;
142 point.y = (it->aabb_max[1] + it->aabb_min[1]) / 2.0;
143 point.z = (it->aabb_max[2] + it->aabb_min[2]) / 2.0;
150 for (
const auto& cost_source : cost_sources)
151 cost += cost_source.getVolume() * cost_source.cost;
156 const std::set<CostSource>& b)
158 cost_sources.clear();
160 for (
const auto& source_a : a)
161 for (
const auto& source_b : b)
163 tmp.
aabb_min[0] = std::max(source_a.aabb_min[0], source_b.aabb_min[0]);
164 tmp.
aabb_min[1] = std::max(source_a.aabb_min[1], source_b.aabb_min[1]);
165 tmp.
aabb_min[2] = std::max(source_a.aabb_min[2], source_b.aabb_min[2]);
167 tmp.
aabb_max[0] = std::min(source_a.aabb_max[0], source_b.aabb_max[0]);
168 tmp.
aabb_max[1] = std::min(source_a.aabb_max[1], source_b.aabb_max[1]);
169 tmp.
aabb_max[2] = std::min(source_a.aabb_max[2], source_b.aabb_max[2]);
174 tmp.
cost = std::max(source_a.cost, source_b.cost);
175 cost_sources.insert(tmp);
182 for (
auto it = cost_sources.begin(); it != cost_sources.end(); ++it)
184 double vol = it->getVolume() * overlap_fraction;
185 std::vector<std::set<CostSource>::iterator>
remove;
187 for (
auto jt = ++it1; jt != cost_sources.end(); ++jt)
189 p[0] = std::max(it->aabb_min[0], jt->aabb_min[0]);
190 p[1] = std::max(it->aabb_min[1], jt->aabb_min[1]);
191 p[2] = std::max(it->aabb_min[2], jt->aabb_min[2]);
193 q[0] = std::min(it->aabb_max[0], jt->aabb_max[0]);
194 q[1] = std::min(it->aabb_max[1], jt->aabb_max[1]);
195 q[2] = std::min(it->aabb_max[2], jt->aabb_max[2]);
197 if (p[0] >= q[0] || p[1] >= q[1] || p[2] >= q[2])
200 double intersect_volume = (q[0] - p[0]) * (q[1] - p[1]) * (q[2] - p[2]);
201 if (intersect_volume >= vol)
202 remove.push_back(jt);
204 for (
auto&
r :
remove)
205 cost_sources.erase(
r);
209 void removeCostSources(std::set<CostSource>& cost_sources,
const std::set<CostSource>& cost_sources_to_remove,
210 double overlap_fraction)
214 for (
const auto& source_remove : cost_sources_to_remove)
216 std::vector<std::set<CostSource>::iterator>
remove;
217 std::set<CostSource> add;
218 for (
auto it = cost_sources.begin(); it != cost_sources.end(); ++it)
220 p[0] = std::max(it->aabb_min[0], source_remove.aabb_min[0]);
221 p[1] = std::max(it->aabb_min[1], source_remove.aabb_min[1]);
222 p[2] = std::max(it->aabb_min[2], source_remove.aabb_min[2]);
224 q[0] = std::min(it->aabb_max[0], source_remove.aabb_max[0]);
225 q[1] = std::min(it->aabb_max[1], source_remove.aabb_max[1]);
226 q[2] = std::min(it->aabb_max[2], source_remove.aabb_max[2]);
228 if (p[0] >= q[0] || p[1] >= q[1] || p[2] >= q[2])
231 double intersect_volume = (q[0] - p[0]) * (q[1] - p[1]) * (q[2] - p[2]);
232 if (intersect_volume >= it->getVolume() * overlap_fraction)
233 remove.push_back(it);
237 for (
int i = 0; i < 3; ++i)
240 if (it->aabb_max[i] > q[i])
247 if (it->aabb_min[i] < p[i])
256 for (
auto&
r :
remove)
257 cost_sources.erase(
r);
258 cost_sources.insert(add.begin(), add.end());
264 msg.cost_density = cost_source.
cost;
265 msg.aabb_min.x = cost_source.
aabb_min[0];
266 msg.aabb_min.y = cost_source.
aabb_min[1];
267 msg.aabb_min.z = cost_source.
aabb_min[2];
268 msg.aabb_max.x = cost_source.
aabb_max[0];
269 msg.aabb_max.y = cost_source.
aabb_max[1];
270 msg.aabb_max.z = cost_source.
aabb_max[2];
277 msg.depth = contact.
depth;
void getCostMarkers(visualization_msgs::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources)
double cost
The partial cost (the probability of existance for the object there is a collision with) ...
boost::array< double, 3 > aabb_min
The minimum bound of the AABB defining the volume responsible for this partial cost.
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)
A body attached to a robot link.
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)
boost::array< double, 3 > aabb_max
The maximum bound of the AABB defining the volume responsible for this partial cost.
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
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)
void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m)
A body in the environment.
When collision costs are computed, this structure contains information about the partial cost incurre...