38 #include <rclcpp/clock.hpp>
39 #include <rclcpp/time.hpp>
40 #include <tf2_eigen/tf2_eigen.hpp>
44 void getCostMarkers(visualization_msgs::msg::MarkerArray& arr,
const std::string& frame_id,
45 std::set<CostSource>& cost_sources)
47 std_msgs::msg::ColorRGBA color;
52 getCostMarkers(arr, frame_id, cost_sources, color, rclcpp::Duration(60, 0));
58 std_msgs::msg::ColorRGBA color;
66 void getCostMarkers(visualization_msgs::msg::MarkerArray& arr,
const std::string& frame_id,
67 std::set<CostSource>& cost_sources,
const std_msgs::msg::ColorRGBA& color,
68 const rclcpp::Duration& lifetime)
71 for (
const auto& cost_source : cost_sources)
73 visualization_msgs::msg::Marker mk;
74 mk.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
75 mk.header.frame_id = frame_id;
76 mk.ns =
"cost_source";
78 mk.type = visualization_msgs::msg::Marker::CUBE;
79 mk.action = visualization_msgs::msg::Marker::ADD;
80 mk.pose.position.x = (cost_source.aabb_max[0] + cost_source.aabb_min[0]) / 2.0;
81 mk.pose.position.y = (cost_source.aabb_max[1] + cost_source.aabb_min[1]) / 2.0;
82 mk.pose.position.z = (cost_source.aabb_max[2] + cost_source.aabb_min[2]) / 2.0;
83 mk.pose.orientation.x = 0.0;
84 mk.pose.orientation.y = 0.0;
85 mk.pose.orientation.z = 0.0;
86 mk.pose.orientation.w = 1.0;
87 mk.scale.x = cost_source.aabb_max[0] - cost_source.aabb_min[0];
88 mk.scale.y = cost_source.aabb_max[1] - cost_source.aabb_min[1];
89 mk.scale.z = cost_source.aabb_max[2] - cost_source.aabb_min[2];
91 if (mk.color.a == 0.0)
93 mk.lifetime = lifetime;
94 arr.markers.push_back(mk);
100 const rclcpp::Duration& lifetime,
double radius)
103 std::map<std::string, unsigned> ns_counts;
105 for (
const auto& collision : con)
107 for (
const auto& contact : collision.second)
109 std::string ns_name = contact.body_name_1 +
"=" + contact.body_name_2;
110 if (ns_counts.find(ns_name) == ns_counts.end())
112 ns_counts[ns_name] = 0;
116 ns_counts[ns_name]++;
118 visualization_msgs::msg::Marker mk;
119 mk.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
120 mk.header.frame_id = frame_id;
122 mk.id = ns_counts[ns_name];
123 mk.type = visualization_msgs::msg::Marker::SPHERE;
124 mk.action = visualization_msgs::msg::Marker::ADD;
125 mk.pose.position.x = contact.pos.x();
126 mk.pose.position.y = contact.pos.y();
127 mk.pose.position.z = contact.pos.z();
128 mk.pose.orientation.x = 0.0;
129 mk.pose.orientation.y = 0.0;
130 mk.pose.orientation.z = 0.0;
131 mk.pose.orientation.w = 1.0;
132 mk.scale.x = mk.scale.y = mk.scale.z = radius * 2.0;
134 if (mk.color.a == 0.0)
136 mk.lifetime = lifetime;
137 arr.markers.push_back(mk);
144 if (cost_sources.empty())
146 auto it = cost_sources.begin();
147 for (std::size_t i = 0; i < 4 * cost_sources.size() / 5; ++i)
149 point.x = (it->aabb_max[0] + it->aabb_min[0]) / 2.0;
150 point.y = (it->aabb_max[1] + it->aabb_min[1]) / 2.0;
151 point.z = (it->aabb_max[2] + it->aabb_min[2]) / 2.0;
158 for (
const auto& cost_source : cost_sources)
159 cost += cost_source.getVolume() * cost_source.cost;
164 const std::set<CostSource>& b)
166 cost_sources.clear();
168 for (
const auto& source_a : a)
170 for (
const auto& source_b : b)
172 tmp.
aabb_min[0] = std::max(source_a.aabb_min[0], source_b.aabb_min[0]);
173 tmp.
aabb_min[1] = std::max(source_a.aabb_min[1], source_b.aabb_min[1]);
174 tmp.
aabb_min[2] = std::max(source_a.aabb_min[2], source_b.aabb_min[2]);
176 tmp.
aabb_max[0] = std::min(source_a.aabb_max[0], source_b.aabb_max[0]);
177 tmp.
aabb_max[1] = std::min(source_a.aabb_max[1], source_b.aabb_max[1]);
178 tmp.
aabb_max[2] = std::min(source_a.aabb_max[2], source_b.aabb_max[2]);
182 tmp.
cost = std::max(source_a.cost, source_b.cost);
183 cost_sources.insert(tmp);
191 for (
auto it = cost_sources.begin(); it != cost_sources.end(); ++it)
193 const double vol = it->getVolume() * overlap_fraction;
194 std::vector<std::set<CostSource>::iterator> remove;
196 for (
auto jt = ++it1; jt != cost_sources.end(); ++jt)
198 p[0] = std::max(it->aabb_min[0], jt->aabb_min[0]);
199 p[1] = std::max(it->aabb_min[1], jt->aabb_min[1]);
200 p[2] = std::max(it->aabb_min[2], jt->aabb_min[2]);
202 q[0] = std::min(it->aabb_max[0], jt->aabb_max[0]);
203 q[1] = std::min(it->aabb_max[1], jt->aabb_max[1]);
204 q[2] = std::min(it->aabb_max[2], jt->aabb_max[2]);
206 if (p[0] >= q[0] || p[1] >= q[1] || p[2] >= q[2])
209 const double intersect_volume = (q[0] - p[0]) * (q[1] - p[1]) * (q[2] - p[2]);
210 if (intersect_volume >= vol)
211 remove.push_back(jt);
213 for (
auto& r : remove)
214 cost_sources.erase(r);
218 void removeCostSources(std::set<CostSource>& cost_sources,
const std::set<CostSource>& cost_sources_to_remove,
219 const double overlap_fraction)
223 for (
const auto& source_remove : cost_sources_to_remove)
225 std::vector<std::set<CostSource>::iterator> remove;
226 std::set<CostSource> add;
227 for (
auto it = cost_sources.begin(); it != cost_sources.end(); ++it)
229 p[0] = std::max(it->aabb_min[0], source_remove.aabb_min[0]);
230 p[1] = std::max(it->aabb_min[1], source_remove.aabb_min[1]);
231 p[2] = std::max(it->aabb_min[2], source_remove.aabb_min[2]);
233 q[0] = std::min(it->aabb_max[0], source_remove.aabb_max[0]);
234 q[1] = std::min(it->aabb_max[1], source_remove.aabb_max[1]);
235 q[2] = std::min(it->aabb_max[2], source_remove.aabb_max[2]);
237 if (p[0] >= q[0] || p[1] >= q[1] || p[2] >= q[2])
240 const double intersect_volume = (q[0] - p[0]) * (q[1] - p[1]) * (q[2] - p[2]);
241 if (intersect_volume >= it->getVolume() * overlap_fraction)
243 remove.push_back(it);
248 for (
int i = 0; i < 3; ++i)
251 if (it->aabb_max[i] > q[i])
258 if (it->aabb_min[i] < p[i])
267 for (
auto& r : remove)
268 cost_sources.erase(r);
269 cost_sources.insert(add.begin(), add.end());
275 msg.cost_density = cost_source.
cost;
276 msg.aabb_min.x = cost_source.
aabb_min[0];
277 msg.aabb_min.y = cost_source.
aabb_min[1];
278 msg.aabb_min.z = cost_source.
aabb_min[2];
279 msg.aabb_max.x = cost_source.
aabb_max[0];
280 msg.aabb_max.y = cost_source.
aabb_max[1];
281 msg.aabb_max.z = cost_source.
aabb_max[2];
286 msg.position = tf2::toMsg(contact.
pos);
287 msg.normal = tf2::toMsg2(contact.
normal);
288 msg.depth = contact.
depth;
@ ROBOT_LINK
A link on the robot.
@ ROBOT_ATTACHED
A body attached to a robot link.
@ WORLD_OBJECT
A body in the environment.
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.
When collision costs are computed, this structure contains information about the partial cost incurre...
std::array< double, 3 > aabb_max
The maximum bound of the AABB defining the volume responsible for this partial cost.
double cost
The partial cost (the probability of existence for the object there is a collision with)
std::array< double, 3 > aabb_min
The minimum bound of the AABB defining the volume responsible for this partial cost.