65 const octomath::Vector3& position,
double& intensity, octomath::Vector3& gradient);
68 double cell_bbx_search_distance,
double allowed_angle_divergence,
69 bool estimate_depth,
double iso_value,
double metaball_radius_multiple)
73 RCLCPP_ERROR(getLogger(),
"No valid Object passed in, cannot refine Normals!");
78 RCLCPP_WARN(getLogger(),
"There do not appear to be any contacts, so there is nothing to refine!");
87 const std::string contact1 = contact.first.first;
88 const std::string contact2 = contact.first.second;
89 std::string octomap_name =
"";
90 std::vector<collision_detection::Contact>& contact_vector = contact.second;
92 if (contact1.find(
"octomap") != std::string::npos)
94 octomap_name = contact1;
96 else if (contact2.find(
"octomap") != std::string::npos)
98 octomap_name = contact2;
105 if (!object->shapes_.empty())
107 const shapes::ShapeConstPtr& shape =
object->shapes_[0];
108 const std::shared_ptr<const shapes::OcTree> shape_octree = std::dynamic_pointer_cast<const shapes::OcTree>(shape);
111 double cell_size = 0;
112 std::shared_ptr<const octomap::OcTree> octree = shape_octree->octree;
113 cell_size = octree->getResolution();
114 for (
auto& contact_info : contact_vector)
116 const Eigen::Vector3d& point = contact_info.pos;
117 const Eigen::Vector3d& normal = contact_info.normal;
119 const octomath::Vector3 contact_point(point[0], point[1], point[2]);
120 const octomath::Vector3 contact_normal(normal[0], normal[1], normal[2]);
121 const octomath::Vector3 diagonal = octomath::Vector3(1, 1, 1);
122 const octomath::Vector3 bbx_min = contact_point - diagonal * cell_size * cell_bbx_search_distance;
123 const octomath::Vector3 bbx_max = contact_point + diagonal * cell_size * cell_bbx_search_distance;
124 octomap::point3d_list node_centers;
125 octomap::OcTreeBaseImpl<octomap::OcTreeNode, octomap::AbstractOccupancyOcTree>::leaf_bbx_iterator it =
126 octree->begin_leafs_bbx(bbx_min, bbx_max);
127 octomap::OcTreeBaseImpl<octomap::OcTreeNode, octomap::AbstractOccupancyOcTree>::leaf_bbx_iterator leafs_end =
128 octree->end_leafs_bbx();
130 for (; it != leafs_end; ++it)
132 const octomap::point3d pt = it.getCoordinate();
133 if (octree->isNodeOccupied(*it))
135 node_centers.push_back(pt);
153 n, depth, estimate_depth))
156 const double divergence = contact_normal.angleTo(n);
157 if (divergence > allowed_angle_divergence)
164 contact_info.normal = Eigen::Vector3d(n.x(), n.y(), n.z());
168 contact_info.depth = depth;
178 double r_multiple,
const octomath::Vector3& contact_point, octomath::Vector3& normal,
179 double& depth,
bool estimate_depth)
183 octomath::Vector3 surface_point;
184 if (
findSurface(cloud, spacing, iso_value, r_multiple, contact_point, surface_point, normal))
186 depth = normal.dot(surface_point - contact_point);
196 octomath::Vector3 gradient;
197 double intensity = 0;
198 if (
sampleCloud(cloud, spacing, r_multiple, contact_point, intensity, gradient))
200 normal = gradient.normalized();
214bool findSurface(
const octomap::point3d_list& cloud,
double spacing,
double iso_value,
double r_multiple,
215 const octomath::Vector3& seed, octomath::Vector3& surface_point, octomath::Vector3& normal)
217 octomath::Vector3 p = seed, dp, gs;
218 const int iterations = 10;
219 const double epsilon = 1e-10;
220 double intensity = 0;
221 for (
int i = 0; i < iterations; ++i)
223 if (!
sampleCloud(cloud, spacing, r_multiple, p, intensity, gs))
225 const double s = iso_value - intensity;
226 dp = (gs * -s) * (1.0 / std::max(gs.dot(gs), epsilon));
228 if (dp.dot(dp) < epsilon)
231 normal = gs.normalized();
239bool sampleCloud(
const octomap::point3d_list& cloud,
double spacing,
double r_multiple,
240 const octomath::Vector3& position,
double& intensity, octomath::Vector3& gradient)
243 gradient = octomath::Vector3(0, 0, 0);
245 const double r = r_multiple * spacing;
248 const int nn = cloud.size();
255 double a = 0, b = 0, c = 0, r2 = 0, r4 = 0, r6 = 0, a1 = 0, b1 = 0, c1 = 0, a2 = 0, b2 = 0, c2 = 0;
256 const bool wyvill =
true;
258 for (
const octomath::Vector3& v : cloud)
277 RCLCPP_ERROR(getLogger(),
"This should not be called!");
281 octomath::Vector3 f_grad(0, 0, 0);
283 octomath::Vector3 pos = position - v;
284 const double r = pos.norm();
285 pos = pos * (1.0 / r);
290 const double r2 = r * r;
291 const double r3 = r * r2;
292 const double r4 = r2 * r2;
293 const double r5 = r3 * r2;
294 const double r6 = r3 * r3;
298 f_val = (a1 * r6 + b1 * r4 + c1 * r2 + 1);
299 f_grad = pos * (a2 * r5 + b2 * r3 + c2 * r);
303 RCLCPP_ERROR(getLogger(),
"This should not be called!");
304 const double r_scaled = r / r;
306 f_val = pow((1 - r_scaled), 4) * (4 * r_scaled + 1);
307 f_grad = pos * (-4.0 / r * pow(1.0 - r_scaled, 3) * (4.0 * r_scaled + 1.0) + 4.0 / r * pow(1 - r_scaled, 4));
bool getMetaballSurfaceProperties(const octomap::point3d_list &cloud, double spacing, double iso_value, double r_multiple, const octomath::Vector3 &contact_point, octomath::Vector3 &normal, double &depth, bool estimate_depth)
bool findSurface(const octomap::point3d_list &cloud, double spacing, double iso_value, double r_multiple, const octomath::Vector3 &seed, octomath::Vector3 &surface_point, octomath::Vector3 &normal)
int refineContactNormals(const World::ObjectConstPtr &object, CollisionResult &res, double cell_bbx_search_distance=1.0, double allowed_angle_divergence=0.0, bool estimate_depth=false, double iso_value=0.5, double metaball_radius_multiple=1.5)
Re-proceses contact normals for an octomap by estimating a metaball iso-surface using the centers of ...