collision_distance_field_types.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: E. Gil Jones */
36 
41 #include <ros/console.h>
42 #include <memory>
43 
44 const static double EPSILON = 0.0001;
45 
46 std::vector<collision_detection::CollisionSphere>
47 collision_detection::determineCollisionSpheres(const bodies::Body* body, Eigen::Isometry3d& relative_transform)
48 {
49  std::vector<collision_detection::CollisionSphere> css;
50  if (body->getType() == shapes::ShapeType::SPHERE)
51  {
52  bodies::BoundingSphere bsphere;
53  body->computeBoundingSphere(bsphere);
54  if (bsphere.radius > 0.0)
55  {
56  css.push_back(collision_detection::CollisionSphere{ bsphere.center, bsphere.radius });
57  }
58  }
59  else
60  {
62  body->computeBoundingCylinder(cyl);
63  if (cyl.radius > 0.0 && cyl.length > 0.0)
64  {
65  unsigned int num_points = ceil(cyl.length / (cyl.radius / 2.0));
66  double spacing = cyl.length / ((num_points * 1.0) - 1.0);
67  relative_transform = cyl.pose;
68 
69  for (unsigned int i = 1; i < num_points - 1; i++)
70  {
72  relative_transform * Eigen::Vector3d(0, 0, (-cyl.length / 2.0) + i * spacing), cyl.radius);
73  css.push_back(cs);
74  }
75  }
76  }
77 
78  return css;
79 }
80 
82  const std::vector<CollisionSphere>& sphere_list, const EigenSTL::vector_Vector3d& sphere_centers,
83  GradientInfo& gradient, const collision_detection::CollisionType& type, double tolerance, bool subtract_radii,
84  double maximum_value, bool stop_at_first_collision)
85 {
86  // assumes gradient is properly initialized
87 
88  bool in_collision = false;
89  for (unsigned int i = 0; i < sphere_list.size(); i++)
90  {
91  Eigen::Vector3d p = sphere_centers[i];
92  Eigen::Vector3d grad(0, 0, 0);
93  bool in_bounds;
94  double dist = this->getDistanceGradient(p.x(), p.y(), p.z(), grad.x(), grad.y(), grad.z(), in_bounds);
95  if (!in_bounds && grad.norm() > 0)
96  {
97  // out of bounds
98  return true;
99  }
100 
101  if (dist < maximum_value)
102  {
103  if (subtract_radii)
104  {
105  dist -= sphere_list[i].radius_;
106 
107  if ((dist < 0) && (-dist >= tolerance))
108  {
109  in_collision = true;
110  }
111 
112  dist = std::abs(dist);
113  }
114  else
115  {
116  if (sphere_list[i].radius_ - dist > tolerance)
117  {
118  in_collision = true;
119  }
120  }
121 
122  if (dist < gradient.closest_distance)
123  {
124  gradient.closest_distance = dist;
125  }
126 
127  if (dist < gradient.distances[i])
128  {
129  gradient.types[i] = type;
130  gradient.distances[i] = dist;
131  gradient.gradients[i] = grad;
132  }
133  }
134 
135  if (stop_at_first_collision && in_collision)
136  {
137  return true;
138  }
139  }
140  return in_collision;
141 }
142 
144  const std::vector<CollisionSphere>& sphere_list,
145  const EigenSTL::vector_Vector3d& sphere_centers,
146  GradientInfo& gradient,
147  const collision_detection::CollisionType& type, double tolerance,
148  bool subtract_radii, double maximum_value,
149  bool stop_at_first_collision)
150 {
151  // assumes gradient is properly initialized
152 
153  bool in_collision = false;
154  for (unsigned int i = 0; i < sphere_list.size(); i++)
155  {
156  Eigen::Vector3d p = sphere_centers[i];
157  Eigen::Vector3d grad;
158  bool in_bounds;
159  double dist = distance_field->getDistanceGradient(p.x(), p.y(), p.z(), grad.x(), grad.y(), grad.z(), in_bounds);
160  if (!in_bounds && grad.norm() > EPSILON)
161  {
162  ROS_DEBUG("Collision sphere point is out of bounds %lf, %lf, %lf", p.x(), p.y(), p.z());
163  return true;
164  }
165 
166  if (dist < maximum_value)
167  {
168  if (subtract_radii)
169  {
170  dist -= sphere_list[i].radius_;
171 
172  if ((dist < 0) && (-dist >= tolerance))
173  {
174  in_collision = true;
175  }
176  }
177  else
178  {
179  if (sphere_list[i].radius_ - dist > tolerance)
180  {
181  in_collision = true;
182  }
183  }
184 
185  if (dist < gradient.closest_distance)
186  {
187  gradient.closest_distance = dist;
188  }
189 
190  if (dist < gradient.distances[i])
191  {
192  gradient.types[i] = type;
193  gradient.distances[i] = dist;
194  gradient.gradients[i] = grad;
195  }
196  }
197 
198  if (stop_at_first_collision && in_collision)
199  {
200  return true;
201  }
202  }
203  return in_collision;
204 }
205 
207  const std::vector<CollisionSphere>& sphere_list,
208  const EigenSTL::vector_Vector3d& sphere_centers,
209  double maximum_value, double tolerance)
210 {
211  for (unsigned int i = 0; i < sphere_list.size(); i++)
212  {
213  Eigen::Vector3d p = sphere_centers[i];
214  Eigen::Vector3d grad;
215  bool in_bounds = true;
216  double dist = distance_field->getDistanceGradient(p.x(), p.y(), p.z(), grad.x(), grad.y(), grad.z(), in_bounds);
217 
218  if (!in_bounds && grad.norm() > 0)
219  {
220  ROS_DEBUG("Collision sphere point is out of bounds");
221  return true;
222  }
223 
224  if ((maximum_value > dist) && (sphere_list[i].radius_ - dist > tolerance))
225  {
226  return true;
227  }
228  }
229 
230  return false;
231 }
232 
234  const std::vector<CollisionSphere>& sphere_list,
235  const EigenSTL::vector_Vector3d& sphere_centers,
236  double maximum_value, double tolerance, unsigned int num_coll,
237  std::vector<unsigned int>& colls)
238 {
239  colls.clear();
240  for (unsigned int i = 0; i < sphere_list.size(); i++)
241  {
242  Eigen::Vector3d p = sphere_centers[i];
243  Eigen::Vector3d grad;
244  bool in_bounds = true;
245  double dist = distance_field->getDistanceGradient(p.x(), p.y(), p.z(), grad.x(), grad.y(), grad.z(), in_bounds);
246  if (!in_bounds && (grad.norm() > 0))
247  {
248  ROS_DEBUG("Collision sphere point is out of bounds");
249  return true;
250  }
251  if (maximum_value > dist && (sphere_list[i].radius_ - dist > tolerance))
252  {
253  if (num_coll == 0)
254  {
255  return true;
256  }
257 
258  colls.push_back(i);
259  if (colls.size() >= num_coll)
260  {
261  return true;
262  }
263  }
264  }
265 
266  return !colls.empty();
267 }
268 
272 
274  double padding)
275 {
276  std::vector<shapes::ShapeConstPtr> shapes;
277  EigenSTL::vector_Isometry3d poses(1, Eigen::Isometry3d::Identity());
278 
279  shapes.push_back(shape);
280  init(shapes, poses, resolution, padding);
281 }
282 
283 collision_detection::BodyDecomposition::BodyDecomposition(const std::vector<shapes::ShapeConstPtr>& shapes,
284  const EigenSTL::vector_Isometry3d& poses, double resolution,
285  double padding)
286 {
287  init(shapes, poses, resolution, padding);
288 }
289 
290 void collision_detection::BodyDecomposition::init(const std::vector<shapes::ShapeConstPtr>& shapes,
291  const EigenSTL::vector_Isometry3d& poses, double resolution,
292  double padding)
293 {
294  bodies_.clear();
295  for (unsigned int i = 0; i < shapes.size(); i++)
296  {
297  bodies_.addBody(shapes[i].get(), poses[i], padding);
298  }
299 
300  // collecting collision spheres
301  collision_spheres_.clear();
302  relative_collision_points_.clear();
303  std::vector<CollisionSphere> body_spheres;
304  EigenSTL::vector_Vector3d body_collision_points;
305  for (unsigned int i = 0; i < bodies_.getCount(); i++)
306  {
307  body_spheres.clear();
308  body_collision_points.clear();
309 
310  body_spheres = determineCollisionSpheres(bodies_.getBody(i), relative_cylinder_pose_);
311  collision_spheres_.insert(collision_spheres_.end(), body_spheres.begin(), body_spheres.end());
312 
313  distance_field::findInternalPointsConvex(*bodies_.getBody(i), resolution, body_collision_points);
314  relative_collision_points_.insert(relative_collision_points_.end(), body_collision_points.begin(),
315  body_collision_points.end());
316  }
317 
318  sphere_radii_.resize(collision_spheres_.size());
319  for (unsigned int i = 0; i < collision_spheres_.size(); i++)
320  {
321  sphere_radii_[i] = collision_spheres_[i].radius_;
322  }
323 
324  // computing bounding sphere
325  std::vector<bodies::BoundingSphere> bounding_spheres(bodies_.getCount());
326  for (unsigned int i = 0; i < bodies_.getCount(); i++)
327  {
328  bodies_.getBody(i)->computeBoundingSphere(bounding_spheres[i]);
329  }
330  bodies::mergeBoundingSpheres(bounding_spheres, relative_bounding_sphere_);
331 
332  ROS_DEBUG_STREAM("BodyDecomposition generated " << collision_spheres_.size() << " collision spheres out of "
333  << shapes.size() << " shapes");
334 }
335 
337 {
338  bodies_.clear();
339 }
340 
342  const BodyDecompositionConstPtr& body_decomposition)
343  : body_decomposition_(body_decomposition)
344 {
345  posed_collision_points_ = body_decomposition_->getCollisionPoints();
346 }
347 
349  const BodyDecompositionConstPtr& body_decomposition, const Eigen::Isometry3d& trans)
350  : body_decomposition_(body_decomposition)
351 {
352  updatePose(trans);
353 }
354 
356  const std::shared_ptr<const octomap::OcTree>& octree)
357  : body_decomposition_()
358 {
359  int num_nodes = octree->getNumLeafNodes();
360  posed_collision_points_.reserve(num_nodes);
361  for (octomap::OcTree::tree_iterator tree_iter = octree->begin_tree(); tree_iter != octree->end_tree(); ++tree_iter)
362  {
363  Eigen::Vector3d p = Eigen::Vector3d(tree_iter.getX(), tree_iter.getY(), tree_iter.getZ());
364  posed_collision_points_.push_back(p);
365  }
366 }
367 
369 {
370  if (body_decomposition_)
371  {
372  posed_collision_points_.resize(body_decomposition_->getCollisionPoints().size());
373 
374  for (unsigned int i = 0; i < body_decomposition_->getCollisionPoints().size(); i++)
375  {
376  posed_collision_points_[i] = trans * body_decomposition_->getCollisionPoints()[i];
377  }
378  }
379 }
380 
382  const BodyDecompositionConstPtr& body_decomposition)
383  : body_decomposition_(body_decomposition)
384 {
385  posed_bounding_sphere_center_ = body_decomposition_->getRelativeBoundingSphere().center;
386  sphere_centers_.resize(body_decomposition_->getCollisionSpheres().size());
387  updatePose(Eigen::Isometry3d::Identity());
388 }
389 
391 {
392  // updating sphere centers
393  posed_bounding_sphere_center_ = trans * body_decomposition_->getRelativeBoundingSphere().center;
394  for (unsigned int i = 0; i < body_decomposition_->getCollisionSpheres().size(); i++)
395  {
396  sphere_centers_[i] = trans * body_decomposition_->getCollisionSpheres()[i].relative_vec_;
397  }
398 
399  // updating collision points
400  if (!body_decomposition_->getCollisionPoints().empty())
401  {
402  posed_collision_points_.resize(body_decomposition_->getCollisionPoints().size());
403  for (unsigned int i = 0; i < body_decomposition_->getCollisionPoints().size(); i++)
404  {
405  posed_collision_points_[i] = trans * body_decomposition_->getCollisionPoints()[i];
406  }
407  }
408 }
409 
410 bool collision_detection::doBoundingSpheresIntersect(const PosedBodySphereDecompositionConstPtr& p1,
411  const PosedBodySphereDecompositionConstPtr& p2)
412 {
413  Eigen::Vector3d p1_sphere_center = p1->getBoundingSphereCenter();
414  Eigen::Vector3d p2_sphere_center = p2->getBoundingSphereCenter();
415  double p1_radius = p1->getBoundingSphereRadius();
416  double p2_radius = p2->getBoundingSphereRadius();
417 
418  double dist = (p1_sphere_center - p2_sphere_center).squaredNorm();
419  return dist < (p1_radius + p2_radius);
420 }
421 
423  const std_msgs::ColorRGBA& color, const std::string& frame_id, const std::string& ns, const ros::Duration& dur,
424  const std::vector<PosedBodySphereDecompositionPtr>& posed_decompositions, visualization_msgs::MarkerArray& arr)
425 {
426  unsigned int count = 0;
427  for (const PosedBodySphereDecompositionPtr& posed_decomposition : posed_decompositions)
428  {
429  if (posed_decomposition)
430  {
431  for (unsigned int j = 0; j < posed_decomposition->getCollisionSpheres().size(); j++)
432  {
433  visualization_msgs::Marker sphere;
434  sphere.type = visualization_msgs::Marker::SPHERE;
435  sphere.header.stamp = ros::Time::now();
436  sphere.header.frame_id = frame_id;
437  sphere.ns = ns;
438  sphere.id = count++;
439  sphere.lifetime = dur;
440  sphere.color = color;
441  sphere.scale.x = sphere.scale.y = sphere.scale.z = posed_decomposition->getCollisionSpheres()[j].radius_ * 2.0;
442  sphere.pose.position.x = posed_decomposition->getSphereCenters()[j].x();
443  sphere.pose.position.y = posed_decomposition->getSphereCenters()[j].y();
444  sphere.pose.position.z = posed_decomposition->getSphereCenters()[j].z();
445  arr.markers.push_back(sphere);
446  }
447  }
448  }
449 }
450 
452  const std::string& frame_id, const std::string& ns, const ros::Duration& /*dur*/,
453  const std::vector<PosedBodySphereDecompositionPtr>& posed_decompositions,
454  const std::vector<PosedBodySphereDecompositionVectorPtr>& posed_vector_decompositions,
455  const std::vector<GradientInfo>& gradients, visualization_msgs::MarkerArray& arr)
456 {
457  if (gradients.size() != posed_decompositions.size() + posed_vector_decompositions.size())
458  {
459  ROS_WARN_NAMED("collision_distance_field", "Size mismatch between gradients %u and decompositions %u",
460  (unsigned int)gradients.size(),
461  (unsigned int)(posed_decompositions.size() + posed_vector_decompositions.size()));
462  return;
463  }
464  for (unsigned int i = 0; i < gradients.size(); i++)
465  {
466  for (unsigned int j = 0; j < gradients[i].distances.size(); j++)
467  {
468  visualization_msgs::Marker arrow_mark;
469  arrow_mark.header.frame_id = frame_id;
470  arrow_mark.header.stamp = ros::Time::now();
471  if (ns.empty())
472  {
473  arrow_mark.ns = "self_coll_gradients";
474  }
475  else
476  {
477  arrow_mark.ns = ns;
478  }
479  arrow_mark.id = i * 1000 + j;
480  double xscale = 0.0;
481  double yscale = 0.0;
482  double zscale = 0.0;
483  if (gradients[i].distances[j] > 0.0 && gradients[i].distances[j] != DBL_MAX)
484  {
485  if (gradients[i].gradients[j].norm() > 0.0)
486  {
487  xscale = gradients[i].gradients[j].x() / gradients[i].gradients[j].norm();
488  yscale = gradients[i].gradients[j].y() / gradients[i].gradients[j].norm();
489  zscale = gradients[i].gradients[j].z() / gradients[i].gradients[j].norm();
490  }
491  else
492  {
493  ROS_DEBUG_NAMED("collision_distance_field", "Negative length for %u %d %lf", i, arrow_mark.id,
494  gradients[i].gradients[j].norm());
495  }
496  }
497  else
498  {
499  ROS_DEBUG_NAMED("collision_distance_field", "Negative dist %lf for %u %d", gradients[i].distances[j], i,
500  arrow_mark.id);
501  }
502  arrow_mark.points.resize(2);
503  if (i < posed_decompositions.size())
504  {
505  arrow_mark.points[1].x = posed_decompositions[i]->getSphereCenters()[j].x();
506  arrow_mark.points[1].y = posed_decompositions[i]->getSphereCenters()[j].y();
507  arrow_mark.points[1].z = posed_decompositions[i]->getSphereCenters()[j].z();
508  }
509  else
510  {
511  arrow_mark.points[1].x =
512  posed_vector_decompositions[i - posed_decompositions.size()]->getSphereCenters()[j].x();
513  arrow_mark.points[1].y =
514  posed_vector_decompositions[i - posed_decompositions.size()]->getSphereCenters()[j].y();
515  arrow_mark.points[1].z =
516  posed_vector_decompositions[i - posed_decompositions.size()]->getSphereCenters()[j].z();
517  }
518  arrow_mark.points[0] = arrow_mark.points[1];
519  arrow_mark.points[0].x -= xscale * gradients[i].distances[j];
520  arrow_mark.points[0].y -= yscale * gradients[i].distances[j];
521  arrow_mark.points[0].z -= zscale * gradients[i].distances[j];
522  arrow_mark.scale.x = 0.01;
523  arrow_mark.scale.y = 0.03;
524  arrow_mark.color.a = 1.0;
525  if (gradients[i].types[j] == collision_detection::SELF)
526  {
527  arrow_mark.color.r = 1.0;
528  arrow_mark.color.g = 0.2;
529  arrow_mark.color.b = .5;
530  }
531  else if (gradients[i].types[j] == collision_detection::INTRA)
532  {
533  arrow_mark.color.r = .2;
534  arrow_mark.color.g = 1.0;
535  arrow_mark.color.b = .5;
536  }
537  else if (gradients[i].types[j] == collision_detection::ENVIRONMENT)
538  {
539  arrow_mark.color.r = .2;
540  arrow_mark.color.g = .5;
541  arrow_mark.color.b = 1.0;
542  }
543  else if (gradients[i].types[j] == collision_detection::NONE)
544  {
545  arrow_mark.color.r = 1.0;
546  arrow_mark.color.g = .2;
547  arrow_mark.color.b = 1.0;
548  }
549  arr.markers.push_back(arrow_mark);
550  }
551  }
552 }
553 
555  const std::string& frame_id, const std::string& ns, const ros::Duration& /*dur*/,
556  const std::vector<PosedBodySphereDecompositionPtr>& posed_decompositions,
557  const std::vector<PosedBodySphereDecompositionVectorPtr>& posed_vector_decompositions,
558  const std::vector<GradientInfo>& gradients, visualization_msgs::MarkerArray& arr)
559 {
560  if (gradients.size() != posed_decompositions.size() + posed_vector_decompositions.size())
561  {
562  ROS_WARN_NAMED("collision_distance_field", "Size mismatch between gradients %zu and decompositions %zu",
563  gradients.size(), posed_decompositions.size() + posed_vector_decompositions.size());
564  return;
565  }
566  for (unsigned int i = 0; i < gradients.size(); i++)
567  {
568  for (unsigned int j = 0; j < gradients[i].types.size(); j++)
569  {
570  visualization_msgs::Marker sphere_mark;
571  sphere_mark.type = visualization_msgs::Marker::SPHERE;
572  sphere_mark.header.frame_id = frame_id;
573  sphere_mark.header.stamp = ros::Time::now();
574  if (ns.empty())
575  {
576  sphere_mark.ns = "distance_collisions";
577  }
578  else
579  {
580  sphere_mark.ns = ns;
581  }
582  sphere_mark.id = i * 1000 + j;
583  if (i < posed_decompositions.size())
584  {
585  sphere_mark.scale.x = sphere_mark.scale.y = sphere_mark.scale.z =
586  posed_decompositions[i]->getCollisionSpheres()[j].radius_ * 2.0;
587  sphere_mark.pose.position.x = posed_decompositions[i]->getSphereCenters()[j].x();
588  sphere_mark.pose.position.y = posed_decompositions[i]->getSphereCenters()[j].y();
589  sphere_mark.pose.position.z = posed_decompositions[i]->getSphereCenters()[j].z();
590  }
591  else
592  {
593  sphere_mark.scale.x = sphere_mark.scale.y = sphere_mark.scale.z =
594  posed_vector_decompositions[i - posed_decompositions.size()]->getCollisionSpheres()[j].radius_ * 2.0;
595  sphere_mark.pose.position.x =
596  posed_vector_decompositions[i - posed_decompositions.size()]->getSphereCenters()[j].x();
597  sphere_mark.pose.position.y =
598  posed_vector_decompositions[i - posed_decompositions.size()]->getSphereCenters()[j].y();
599  sphere_mark.pose.position.z =
600  posed_vector_decompositions[i - posed_decompositions.size()]->getSphereCenters()[j].z();
601  }
602  sphere_mark.pose.orientation.w = 1.0;
603  sphere_mark.color.a = 1.0;
604  if (gradients[i].types[j] == collision_detection::SELF)
605  {
606  sphere_mark.color.r = 1.0;
607  sphere_mark.color.g = 0.2;
608  sphere_mark.color.b = .5;
609  }
610  else if (gradients[i].types[j] == collision_detection::INTRA)
611  {
612  sphere_mark.color.r = .2;
613  sphere_mark.color.g = 1.0;
614  sphere_mark.color.b = .5;
615  }
616  else if (gradients[i].types[j] == collision_detection::ENVIRONMENT)
617  {
618  sphere_mark.color.r = .2;
619  sphere_mark.color.g = .5;
620  sphere_mark.color.b = 1.0;
621  }
622  else
623  {
624  sphere_mark.color.r = 1.0;
625  sphere_mark.color.g = .2;
626  sphere_mark.color.b = 1.0;
627  }
628  arr.markers.push_back(sphere_mark);
629  }
630  }
631 }
collision_detection::PosedBodyPointDecomposition::body_decomposition_
BodyDecompositionConstPtr body_decomposition_
Definition: collision_distance_field_types.h:391
collision_detection::INTRA
@ INTRA
Definition: collision_distance_field_types.h:125
collision_detection::PosedDistanceField::getCollisionSphereGradients
bool getCollisionSphereGradients(const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, GradientInfo &gradient, const CollisionType &type, double tolerance, bool subtract_radii, double maximum_value, bool stop_at_first_collision)
Definition: collision_distance_field_types.cpp:81
bodies::BoundingSphere::radius
double radius
shapes
EigenSTL::vector_Isometry3d
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
collision_detection::CollisionSphere
Definition: collision_distance_field_types.h:97
collision_detection::GradientInfo::types
std::vector< CollisionType > types
Definition: collision_distance_field_types.h:123
collision_detection::determineCollisionSpheres
std::vector< CollisionSphere > determineCollisionSpheres(const bodies::Body *body, Eigen::Isometry3d &relativeTransform)
Definition: collision_distance_field_types.cpp:47
collision_detection::GradientInfo::gradients
EigenSTL::vector_Vector3d gradients
Definition: collision_distance_field_types.h:122
collision_distance_field_types.h
collision_detection::BodyDecomposition::~BodyDecomposition
~BodyDecomposition()
Definition: collision_distance_field_types.cpp:336
collision_detection::PosedDistanceField::getDistanceGradient
double getDistanceGradient(double x, double y, double z, double &gradient_x, double &gradient_y, double &gradient_z, bool &in_bounds) const
Gets not only the distance to the nearest cell but the gradient direction. The point defined by the x...
Definition: collision_distance_field_types.h:188
ROS_DEBUG
#define ROS_DEBUG(...)
collision_detection::CollisionType
CollisionType
Definition: collision_distance_field_types.h:89
collision_detection::SELF
@ SELF
Definition: collision_distance_field_types.h:124
collision_detection::PosedBodySphereDecomposition::posed_bounding_sphere_center_
Eigen::Vector3d posed_bounding_sphere_center_
Definition: collision_distance_field_types.h:367
collision_detection::getProximityGradientMarkers
void getProximityGradientMarkers(const std::string &frame_id, const std::string &ns, const ros::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, const std::vector< PosedBodySphereDecompositionVectorPtr > &posed_vector_decompositions, const std::vector< GradientInfo > &gradients, visualization_msgs::MarkerArray &arr)
Definition: collision_distance_field_types.cpp:451
bodies::Body::computeBoundingCylinder
virtual void computeBoundingCylinder(BoundingCylinder &cylinder) const=0
bodies::BoundingCylinder::radius
double radius
bodies::Body
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
bodies::Body::computeBoundingSphere
virtual void computeBoundingSphere(BoundingSphere &sphere) const=0
get
def get(url)
collision_detection::doBoundingSpheresIntersect
bool doBoundingSpheresIntersect(const PosedBodySphereDecompositionConstPtr &p1, const PosedBodySphereDecompositionConstPtr &p2)
Definition: collision_distance_field_types.cpp:410
collision_detection::PosedBodyPointDecomposition::PosedBodyPointDecomposition
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PosedBodyPointDecomposition(const BodyDecompositionConstPtr &body_decomposition)
Definition: collision_distance_field_types.cpp:341
collision_detection::PosedBodyPointDecomposition::updatePose
void updatePose(const Eigen::Isometry3d &linkTransform)
Definition: collision_distance_field_types.cpp:368
collision_detection::PosedBodyPointDecomposition::posed_collision_points_
EigenSTL::vector_Vector3d posed_collision_points_
Definition: collision_distance_field_types.h:392
bodies::BoundingSphere
console.h
distance_field::DistanceField
DistanceField is an abstract base class for computing distances from sets of 3D obstacle points....
Definition: distance_field.h:91
collision_detection::GradientInfo
Definition: collision_distance_field_types.h:110
collision_detection::getCollisionSphereMarkers
void getCollisionSphereMarkers(const std_msgs::ColorRGBA &color, const std::string &frame_id, const std::string &ns, const ros::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, visualization_msgs::MarkerArray &arr)
Definition: collision_distance_field_types.cpp:422
collision_detection::getCollisionMarkers
void getCollisionMarkers(const std::string &frame_id, const std::string &ns, const ros::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, const std::vector< PosedBodySphereDecompositionVectorPtr > &posed_vector_decompositions, const std::vector< GradientInfo > &gradients, visualization_msgs::MarkerArray &arr)
Definition: collision_distance_field_types.cpp:554
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
bodies::BoundingCylinder::length
double length
bodies::BoundingCylinder
collision_detection::getCollisionSphereGradients
bool getCollisionSphereGradients(const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, GradientInfo &gradient, const CollisionType &type, double tolerance, bool subtract_radii, double maximum_value, bool stop_at_first_collision)
Definition: collision_distance_field_types.cpp:143
EigenSTL::vector_Vector3d
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
distance_field::findInternalPointsConvex
void findInternalPointsConvex(const bodies::Body &body, double resolution, EigenSTL::vector_Vector3d &points)
Find all points on a regular grid that are internal to the body, assuming the body is a convex shape....
Definition: find_internal_points.cpp:39
bodies::Body::getType
shapes::ShapeType getType() const
collision_detection::PosedBodySphereDecomposition::updatePose
void updatePose(const Eigen::Isometry3d &linkTransform)
Definition: collision_distance_field_types.cpp:390
collision_detection::NONE
@ NONE
Definition: collision_distance_field_types.h:123
bodies::BoundingCylinder::pose
Eigen::Isometry3d pose
body_operations.h
collision_detection::BodyDecomposition::init
void init(const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &poses, double resolution, double padding)
Definition: collision_distance_field_types.cpp:290
collision_detection::PosedBodySphereDecomposition::PosedBodySphereDecomposition
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PosedBodySphereDecomposition(const BodyDecompositionConstPtr &body_decomposition)
Definition: collision_distance_field_types.cpp:381
collision_detection::ENVIRONMENT
@ ENVIRONMENT
Definition: collision_distance_field_types.h:126
find_internal_points.h
distance_field.h
distance_field
Namespace for holding classes that generate distance fields.
Definition: distance_field.h:64
EPSILON
const static double EPSILON
Definition: collision_distance_field_types.cpp:44
collision_detection::PosedBodySphereDecomposition::body_decomposition_
BodyDecompositionConstPtr body_decomposition_
Definition: collision_distance_field_types.h:366
collision_detection::getCollisionSphereCollision
bool getCollisionSphereCollision(const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, double maximum_value, double tolerance)
Definition: collision_distance_field_types.cpp:206
bodies::BoundingSphere::center
Eigen::Vector3d center
collision_detection::BodyDecomposition::BodyDecomposition
EIGEN_MAKE_ALIGNED_OPERATOR_NEW BodyDecomposition(const shapes::ShapeConstPtr &shape, double resolution, double padding=0.01)
Definition: collision_distance_field_types.cpp:273
collision_detection::PosedBodySphereDecomposition::sphere_centers_
EigenSTL::vector_Vector3d sphere_centers_
Definition: collision_distance_field_types.h:369
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
bodies::mergeBoundingSpheres
void mergeBoundingSpheres(const std::vector< BoundingSphere > &spheres, BoundingSphere &mergedSphere)
tolerance
S tolerance()
init
void init(const M_string &remappings)
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
ros::Duration
collision_detection::GradientInfo::closest_distance
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double closest_distance
Definition: collision_distance_field_types.h:118
collision_detection::GradientInfo::distances
std::vector< double > distances
Definition: collision_distance_field_types.h:121
fcl::Vector3d
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
ros::Time::now
static Time now()


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:40