48 double origin_y,
double origin_z)
55 , resolution_(resolution)
56 , inv_twice_resolution_(1.0 / (2.0 * resolution_))
60 DistanceField::~DistanceField() =
default;
62 double DistanceField::getDistanceGradient(
double x,
double y,
double z,
double& gradient_x,
double& gradient_y,
63 double& gradient_z,
bool& in_bounds)
const
67 worldToGrid(x, y, z, gx, gy, gz);
71 if (gx < 1 || gy < 1 || gz < 1 || gx >= getXNumCells() - 1 || gy >= getYNumCells() - 1 || gz >= getZNumCells() - 1)
77 return getUninitializedDistance();
88 void DistanceField::getIsoSurfaceMarkers(
double min_distance,
double max_distance,
const std::string& frame_id,
89 const ros::Time stamp, visualization_msgs::Marker& inf_marker)
const
91 inf_marker.points.clear();
92 inf_marker.header.frame_id = frame_id;
93 inf_marker.header.stamp = stamp;
94 inf_marker.ns =
"distance_field";
96 inf_marker.type = visualization_msgs::Marker::CUBE_LIST;
97 inf_marker.action = visualization_msgs::Marker::MODIFY;
98 inf_marker.scale.x = resolution_;
99 inf_marker.scale.y = resolution_;
100 inf_marker.scale.z = resolution_;
101 inf_marker.color.r = 1.0;
102 inf_marker.color.g = 0.0;
103 inf_marker.color.b = 0.0;
104 inf_marker.color.a = 0.1;
107 inf_marker.points.reserve(100000);
108 for (
int x = 0;
x < getXNumCells(); ++
x)
110 for (
int y = 0;
y < getYNumCells(); ++
y)
112 for (
int z = 0;
z < getZNumCells(); ++
z)
116 if (dist >= min_distance && dist <= max_distance)
118 int last = inf_marker.points.size();
119 inf_marker.points.resize(last + 1);
121 gridToWorld(x, y, z, nx, ny, nz);
122 Eigen::Translation3d vec(nx, ny, nz);
123 inf_marker.points[last].x = vec.x();
124 inf_marker.points[last].y = vec.y();
125 inf_marker.points[last].z = vec.z();
132 void DistanceField::getGradientMarkers(
double min_distance,
double max_distance,
const std::string& frame_id,
133 const ros::Time& stamp, visualization_msgs::MarkerArray& marker_array)
const
141 for (
int x = 0;
x < getXNumCells(); ++
x)
143 for (
int y = 0;
y < getYNumCells(); ++
y)
145 for (
int z = 0;
z < getZNumCells(); ++
z)
147 double world_x, world_y, world_z;
148 gridToWorld(x, y, z, world_x, world_y, world_z);
150 double gradient_x, gradient_y, gradient_z;
152 double distance = getDistanceGradient(world_x, world_y, world_z, gradient_x, gradient_y, gradient_z, in_bounds);
155 if (in_bounds &&
distance >= min_distance &&
distance <= max_distance && gradient.norm() > 0)
157 visualization_msgs::Marker marker;
159 marker.header.frame_id = frame_id;
160 marker.header.stamp = stamp;
162 marker.ns =
"distance_field_gradient";
164 marker.type = visualization_msgs::Marker::ARROW;
165 marker.action = visualization_msgs::Marker::ADD;
167 marker.pose.position.x = world_x;
168 marker.pose.position.y = world_y;
169 marker.pose.position.z = world_z;
180 marker.scale.x = getResolution();
181 marker.scale.y = getResolution();
182 marker.scale.z = getResolution();
184 marker.color.r = 0.0;
185 marker.color.g = 0.0;
186 marker.color.b = 1.0;
187 marker.color.a = 1.0;
189 marker_array.markers.push_back(marker);
196 bool DistanceField::getShapePoints(
const shapes::Shape* shape,
const Eigen::Isometry3d& pose,
204 ROS_ERROR_NAMED(
"distance_field",
"Problem dynamic casting shape that claims to be OcTree");
207 getOcTreePoints(oc->
octree.get(), points);
221 void DistanceField::addShapeToField(
const shapes::Shape* shape,
const Eigen::Isometry3d& pose)
224 getShapePoints(shape, pose, &point_vec);
225 addPointsToField(point_vec);
229 void DistanceField::addShapeToField(
const shapes::Shape* shape,
const geometry_msgs::Pose& pose)
231 Eigen::Isometry3d pose_e;
233 addShapeToField(shape, pose_e);
239 double min_x, min_y, min_z;
240 gridToWorld(0, 0, 0, min_x, min_y, min_z);
244 int num_x = getXNumCells();
245 int num_y = getYNumCells();
246 int num_z = getZNumCells();
249 double max_x, max_y, max_z;
250 gridToWorld(num_x, num_y, num_z, max_x, max_y, max_z);
259 if (it.getSize() <= resolution_)
262 points->push_back(
point);
266 double ceil_val = ceil(it.getSize() / resolution_) * resolution_ / 2.0;
267 for (
double x = it.getX() - ceil_val; x <= it.getX() + ceil_val; x += resolution_)
269 for (
double y = it.getY() - ceil_val;
y <= it.getY() + ceil_val;
y += resolution_)
271 for (
double z = it.getZ() - ceil_val;
z <= it.getZ() + ceil_val;
z += resolution_)
285 getOcTreePoints(octree, &points);
286 addPointsToField(points);
289 void DistanceField::moveShapeInField(
const shapes::Shape* shape,
const Eigen::Isometry3d& old_pose,
290 const Eigen::Isometry3d& new_pose)
294 ROS_WARN_NAMED(
"distance_field",
"Move shape not supported for Octree");
307 updatePointsInField(old_point_vec, new_point_vec);
311 void DistanceField::moveShapeInField(
const shapes::Shape* shape,
const geometry_msgs::Pose& old_pose,
312 const geometry_msgs::Pose& new_pose)
314 Eigen::Isometry3d old_pose_e, new_pose_e;
317 moveShapeInField(shape, old_pose_e, new_pose_e);
320 void DistanceField::removeShapeFromField(
const shapes::Shape* shape,
const Eigen::Isometry3d& pose)
329 removePointsFromField(point_vec);
333 void DistanceField::removeShapeFromField(
const shapes::Shape* shape,
const geometry_msgs::Pose& pose)
335 Eigen::Isometry3d pose_e;
337 removeShapeFromField(shape, pose_e);
340 void DistanceField::getPlaneMarkers(
PlaneVisualizationType type,
double length,
double width,
double height,
342 visualization_msgs::Marker& plane_marker)
const
344 plane_marker.header.frame_id = frame_id;
345 plane_marker.header.stamp = stamp;
346 plane_marker.ns =
"distance_field_plane";
348 plane_marker.type = visualization_msgs::Marker::CUBE_LIST;
349 plane_marker.action = visualization_msgs::Marker::ADD;
350 plane_marker.scale.x = resolution_;
351 plane_marker.scale.y = resolution_;
352 plane_marker.scale.z = resolution_;
355 plane_marker.points.reserve(100000);
356 plane_marker.colors.reserve(100000);
373 min_y = -width / 2.0;
382 min_z = -width / 2.0;
391 min_z = -width / 2.0;
411 worldToGrid(min_x, min_y, min_z, min_x_cell, min_y_cell, min_z_cell);
412 worldToGrid(max_x, max_y, max_z, max_x_cell, max_y_cell, max_z_cell);
413 plane_marker.color.a = 1.0;
414 for (
int x = min_x_cell;
x <= max_x_cell; ++
x)
416 for (
int y = min_y_cell;
y <= max_y_cell; ++
y)
418 for (
int z = min_z_cell;
z <= max_z_cell; ++
z)
420 if (!isCellValid(x, y, z))
425 int last = plane_marker.points.size();
426 plane_marker.points.resize(last + 1);
427 plane_marker.colors.resize(last + 1);
429 gridToWorld(x, y, z, nx, ny, nz);
431 plane_marker.points[last].x = vec.x();
432 plane_marker.points[last].y = vec.y();
433 plane_marker.points[last].z = vec.z();
436 plane_marker.colors[last].r = fmax(fmin(0.1 / fabs(dist), 1.0), 0.0);
437 plane_marker.colors[last].g = fmax(fmin(0.05 / fabs(dist), 1.0), 0.0);
438 plane_marker.colors[last].b = fmax(fmin(0.01 / fabs(dist), 1.0), 0.0);
442 plane_marker.colors[last].b = fmax(fmin(0.1 / (dist + 0.001), 1.0), 0.0);
443 plane_marker.colors[last].g = fmax(fmin(0.05 / (dist + 0.001), 1.0), 0.0);
444 plane_marker.colors[last].r = fmax(fmin(0.01 / (dist + 0.001), 1.0), 0.0);
451 void DistanceField::setPoint(
int xCell,
int yCell,
int zCell,
double dist, geometry_msgs::Point&
point,
452 std_msgs::ColorRGBA& color,
double max_distance)
const
455 gridToWorld(xCell, yCell, zCell, wx, wy, wz);
462 color.g = dist / max_distance;
463 color.b = dist / max_distance;
466 void DistanceField::getProjectionPlanes(
const std::string& frame_id,
const ros::Time& stamp,
double max_dist,
467 visualization_msgs::Marker& marker)
const
469 int max_x_cell = getXNumCells();
470 int max_y_cell = getYNumCells();
471 int max_z_cell = getZNumCells();
473 double* x_projection =
new double[max_y_cell * max_z_cell];
474 double* y_projection =
new double[max_z_cell * max_x_cell];
475 double* z_projection =
new double[max_x_cell * max_y_cell];
476 double initial_val = sqrt(INT_MAX);
479 for (
int y = 0;
y < max_y_cell;
y++)
480 for (
int x = 0;
x < max_x_cell;
x++)
481 z_projection[x + y * max_x_cell] = initial_val;
483 for (
int z = 0;
z < max_z_cell;
z++)
484 for (
int y = 0;
y < max_y_cell;
y++)
485 x_projection[y + z * max_y_cell] = initial_val;
487 for (
int z = 0;
z < max_z_cell;
z++)
488 for (
int x = 0;
x < max_x_cell;
x++)
489 y_projection[x + z * max_x_cell] = initial_val;
492 for (
int z = 0;
z < max_z_cell;
z++)
494 for (
int y = 0;
y < max_y_cell;
y++)
496 for (
int x = 0;
x < max_x_cell;
x++)
499 z_projection[
x +
y * max_x_cell] = std::min(dist, z_projection[x + y * max_x_cell]);
500 x_projection[
y +
z * max_y_cell] = std::min(dist, x_projection[y + z * max_y_cell]);
501 y_projection[
x +
z * max_x_cell] = std::min(dist, y_projection[x + z * max_x_cell]);
507 marker.points.clear();
508 marker.header.frame_id = frame_id;
509 marker.header.stamp = stamp;
510 marker.ns =
"distance_field_projection_plane";
512 marker.type = visualization_msgs::Marker::CUBE_LIST;
513 marker.action = visualization_msgs::Marker::MODIFY;
514 marker.scale.x = getResolution();
515 marker.scale.y = getResolution();
516 marker.scale.z = getResolution();
517 marker.color.a = 1.0;
522 marker.points.resize(max_x_cell * max_y_cell + max_y_cell * max_z_cell + max_z_cell * max_x_cell);
523 marker.colors.resize(max_x_cell * max_y_cell + max_y_cell * max_z_cell + max_z_cell * max_x_cell);
526 for (y = 0;
y < max_y_cell;
y++)
528 for (x = 0;
x < max_x_cell;
x++)
530 double dist = z_projection[
x +
y * max_x_cell];
531 setPoint(x, y, z, dist, marker.points[index], marker.colors[index], max_dist);
537 for (z = 0;
z < max_z_cell;
z++)
539 for (y = 0;
y < max_y_cell;
y++)
541 double dist = x_projection[
y +
z * max_y_cell];
542 setPoint(x, y, z, dist, marker.points[index], marker.colors[index], max_dist);
548 for (z = 0;
z < max_z_cell;
z++)
550 for (x = 0;
x < max_x_cell;
x++)
552 double dist = y_projection[
x +
z * max_x_cell];
553 setPoint(x, y, z, dist, marker.points[index], marker.colors[index], max_dist);
559 delete[] x_projection;
561 delete[] y_projection;
563 delete[] z_projection;