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;
147 double getTotalCost(
const std::set<CostSource>& cost_sources)
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]);
171 if (tmp.aabb_min[0] >= tmp.aabb_max[0] || tmp.aabb_min[1] >= tmp.aabb_max[1] || tmp.aabb_min[2] >= tmp.aabb_max[2])
173 tmp.cost = std::max(source_a.cost, source_b.cost);
174 cost_sources.insert(tmp);
178 void removeOverlapping(std::set<CostSource>& cost_sources,
double overlap_fraction)
181 for (
auto it = cost_sources.begin(); it != cost_sources.end(); ++it)
183 double vol = it->getVolume() * overlap_fraction;
184 std::vector<std::set<CostSource>::iterator> remove;
186 for (
auto jt = ++it1; jt != cost_sources.end(); ++jt)
188 p[0] = std::max(it->aabb_min[0], jt->aabb_min[0]);
189 p[1] = std::max(it->aabb_min[1], jt->aabb_min[1]);
190 p[2] = std::max(it->aabb_min[2], jt->aabb_min[2]);
192 q[0] = std::min(it->aabb_max[0], jt->aabb_max[0]);
193 q[1] = std::min(it->aabb_max[1], jt->aabb_max[1]);
194 q[2] = std::min(it->aabb_max[2], jt->aabb_max[2]);
196 if (p[0] >= q[0] || p[1] >= q[1] || p[2] >= q[2])
199 double intersect_volume = (q[0] - p[0]) * (q[1] - p[1]) * (q[2] - p[2]);
200 if (intersect_volume >= vol)
201 remove.push_back(jt);
203 for (
auto& r : remove)
204 cost_sources.erase(r);
208 void removeCostSources(std::set<CostSource>& cost_sources,
const std::set<CostSource>& cost_sources_to_remove,
209 double overlap_fraction)
213 for (
const auto& source_remove : cost_sources_to_remove)
215 std::vector<std::set<CostSource>::iterator> remove;
216 std::set<CostSource>
add;
217 for (
auto it = cost_sources.begin(); it != cost_sources.end(); ++it)
219 p[0] = std::max(it->aabb_min[0], source_remove.aabb_min[0]);
220 p[1] = std::max(it->aabb_min[1], source_remove.aabb_min[1]);
221 p[2] = std::max(it->aabb_min[2], source_remove.aabb_min[2]);
223 q[0] = std::min(it->aabb_max[0], source_remove.aabb_max[0]);
224 q[1] = std::min(it->aabb_max[1], source_remove.aabb_max[1]);
225 q[2] = std::min(it->aabb_max[2], source_remove.aabb_max[2]);
227 if (p[0] >= q[0] || p[1] >= q[1] || p[2] >= q[2])
230 double intersect_volume = (q[0] - p[0]) * (q[1] - p[1]) * (q[2] - p[2]);
231 if (intersect_volume >= it->getVolume() * overlap_fraction)
232 remove.push_back(it);
236 for (
int i = 0; i < 3; ++i)
239 if (it->aabb_max[i] > q[i])
246 if (it->aabb_min[i] < p[i])
249 cs.aabb_max[i] = p[i];
255 for (
auto& r : remove)
256 cost_sources.erase(r);
257 cost_sources.insert(
add.begin(),
add.end());
261 void costSourceToMsg(
const CostSource& cost_source, moveit_msgs::CostSource& msg)
263 msg.cost_density = cost_source.cost;
264 msg.aabb_min.x = cost_source.aabb_min[0];
265 msg.aabb_min.y = cost_source.aabb_min[1];
266 msg.aabb_min.z = cost_source.aabb_min[2];
267 msg.aabb_max.x = cost_source.aabb_max[0];
268 msg.aabb_max.y = cost_source.aabb_max[1];
269 msg.aabb_max.z = cost_source.aabb_max[2];
272 void contactToMsg(
const Contact& contact, moveit_msgs::ContactInformation& msg)
276 msg.depth = contact.depth;
277 msg.contact_body_1 = contact.body_name_1;
278 msg.contact_body_2 = contact.body_name_2;