moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
collision_distance_field_types.h
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
37#pragma once
38
39#include <vector>
40#include <string>
41#include <algorithm>
42#include <memory>
43#include <float.h>
44
45#include <geometric_shapes/shapes.h>
46#include <geometric_shapes/bodies.h>
47#include <octomap/OcTree.h>
48
52#include <visualization_msgs/msg/marker_array.hpp>
53#include <rclcpp/duration.hpp>
54#include <rclcpp/logging.hpp>
55#include <rclcpp/clock.hpp>
56#include <rclcpp/rclcpp.hpp>
57#include <rclcpp/time.hpp>
58#include <rclcpp/utilities.hpp>
60
61namespace collision_detection
62{
64{
65 NONE = 0,
66 SELF = 1,
67 INTRA = 2,
69};
70
72{
73 CollisionSphere(const Eigen::Vector3d& rel, double radius)
74 {
75 relative_vec_ = rel;
76 radius_ = radius;
77 }
79
80 Eigen::Vector3d relative_vec_;
81 double radius_;
82};
83
85{
87 {
88 }
89
91
94 EigenSTL::vector_Vector3d sphere_locations;
95 std::vector<double> distances;
96 EigenSTL::vector_Vector3d gradients;
97 std::vector<CollisionType> types;
98 std::vector<double> sphere_radii;
99 std::string joint_name;
100
101 void clear()
102 {
103 closest_distance = DBL_MAX;
104 collision = false;
105 sphere_locations.clear();
106 distances.clear();
107 gradients.clear();
108 sphere_radii.clear();
109 joint_name.clear();
110 }
111};
112
113// Defines ConstPtr, WeakPtr... etc
120
122{
123public:
125
126 PosedDistanceField(const Eigen::Vector3d& size, const Eigen::Vector3d& origin, double resolution, double max_distance,
127 bool propagate_negative_distances = false)
128 : distance_field::PropagationDistanceField(size.x(), size.y(), size.z(), resolution, origin.x(), origin.y(),
129 origin.z(), max_distance, propagate_negative_distances)
130 , pose_(Eigen::Isometry3d::Identity())
131 {
132 }
133
134 void updatePose(const Eigen::Isometry3d& transform)
135 {
136 pose_ = transform;
137 }
138
139 const Eigen::Isometry3d& getPose() const
140 {
141 return pose_;
142 }
143
163 double getDistanceGradient(double x, double y, double z, double& gradient_x, double& gradient_y, double& gradient_z,
164 bool& in_bounds) const
165 {
166 // Transpose of a rotation matrix equals its inverse, but computationally cheaper
167 Eigen::Vector3d rel_pos = pose_.linear().transpose() * Eigen::Vector3d(x, y, z);
168 double gx, gy, gz;
169 double res = distance_field::PropagationDistanceField::getDistanceGradient(rel_pos.x(), rel_pos.y(), rel_pos.z(),
170 gx, gy, gz, in_bounds);
171 Eigen::Vector3d grad = pose_ * Eigen::Vector3d(gx, gy, gz);
172 gradient_x = grad.x();
173 gradient_y = grad.y();
174 gradient_z = grad.z();
175 return res;
176 }
177
178 /*
179 * @brief determines a set of gradients of the given collision spheres in the
180 * distance field
181 * @param sphere_list vector of the spheres that approximate a links geometry
182 * @param sphere_centers vector of points which indicate the center of each
183 * sphere in sphere_list
184 * @param gradient output argument to be populated with the resulting gradient
185 * calculation
186 * @param tolerance
187 * @param subtract_radii distance to the sphere centers will be computed by
188 * subtracting the sphere radius from the nearest point
189 * @param maximum_value
190 * @param stop_at_first_collision when true the computation is terminated when
191 * the first collision is found
192 */
193 bool getCollisionSphereGradients(const std::vector<CollisionSphere>& sphere_list,
194 const EigenSTL::vector_Vector3d& sphere_centers, GradientInfo& gradient,
195 const CollisionType& type, double tolerance, bool subtract_radii,
196 double maximum_value, bool stop_at_first_collision);
197
198protected:
199 Eigen::Isometry3d pose_;
200};
201
202// determines set of collision spheres given a posed body; this is BAD!
203// Allocation errors will happen; change this function so it does not return
204// that vector by value
205std::vector<CollisionSphere> determineCollisionSpheres(const bodies::Body* body, Eigen::Isometry3d& relativeTransform);
206
207// determines a set of gradients of the given collision spheres in the distance
208// field
210 const std::vector<CollisionSphere>& sphere_list,
211 const EigenSTL::vector_Vector3d& sphere_centers, GradientInfo& gradient,
212 const CollisionType& type, double tolerance, bool subtract_radii, double maximum_value,
213 bool stop_at_first_collision);
214
216 const std::vector<CollisionSphere>& sphere_list,
217 const EigenSTL::vector_Vector3d& sphere_centers, double maximum_value,
218 double tolerance);
219
221 const std::vector<CollisionSphere>& sphere_list,
222 const EigenSTL::vector_Vector3d& sphere_centers, double maximum_value,
223 double tolerance, unsigned int num_coll, std::vector<unsigned int>& colls);
224
225// forward declaration required for friending apparently
226class BodyDecompositionVector;
227
229{
231
232public:
234
235 BodyDecomposition(const shapes::ShapeConstPtr& shape, double resolution, double padding = 0.01);
236
237 BodyDecomposition(const std::vector<shapes::ShapeConstPtr>& shapes, const EigenSTL::vector_Isometry3d& poses,
238 double resolution, double padding);
239
241
242 Eigen::Isometry3d relative_cylinder_pose_;
243
244 void replaceCollisionSpheres(const std::vector<CollisionSphere>& new_collision_spheres,
245 const Eigen::Isometry3d& new_relative_cylinder_pose)
246 {
247 // std::cerr << "Replacing " << collision_spheres_.size() << " with " <<
248 // new_collision_spheres.size() << '\n';
249 collision_spheres_ = new_collision_spheres;
250 relative_cylinder_pose_ = new_relative_cylinder_pose;
251 }
252
253 const std::vector<CollisionSphere>& getCollisionSpheres() const
254 {
255 return collision_spheres_;
256 }
257
258 const std::vector<double>& getSphereRadii() const
259 {
260 return sphere_radii_;
261 }
262
263 const EigenSTL::vector_Vector3d& getCollisionPoints() const
264 {
266 }
267
268 const bodies::Body* getBody(unsigned int i) const
269 {
270 return bodies_.getBody(i);
271 }
272
273 unsigned int getBodiesCount()
274 {
275 return bodies_.getCount();
276 }
277
278 Eigen::Isometry3d getRelativeCylinderPose() const
279 {
281 }
282
283 const bodies::BoundingSphere& getRelativeBoundingSphere() const
284 {
286 }
287
288protected:
289 void init(const std::vector<shapes::ShapeConstPtr>& shapes, const EigenSTL::vector_Isometry3d& poses,
290 double resolution, double padding);
291
292protected:
293 bodies::BodyVector bodies_;
294
295 bodies::BoundingSphere relative_bounding_sphere_;
296 std::vector<double> sphere_radii_;
297 std::vector<CollisionSphere> collision_spheres_;
298 EigenSTL::vector_Vector3d relative_collision_points_;
299};
300
302{
303public:
305
306 PosedBodySphereDecomposition(const BodyDecompositionConstPtr& body_decomposition);
307
308 const std::vector<CollisionSphere>& getCollisionSpheres() const
309 {
310 return body_decomposition_->getCollisionSpheres();
311 }
312
313 const EigenSTL::vector_Vector3d& getSphereCenters() const
314 {
315 return sphere_centers_;
316 }
317
318 const EigenSTL::vector_Vector3d& getCollisionPoints() const
319 {
321 }
322
323 const std::vector<double>& getSphereRadii() const
324 {
325 return body_decomposition_->getSphereRadii();
326 }
327 const Eigen::Vector3d& getBoundingSphereCenter() const
328 {
330 }
331
333 {
334 return body_decomposition_->getRelativeBoundingSphere().radius;
335 }
336
337 // assumed to be in reference frame, updates the pose of the body,
338 // the collision spheres, and the posed collision points
339 void updatePose(const Eigen::Isometry3d& linkTransform);
340
341protected:
342 BodyDecompositionConstPtr body_decomposition_;
344 EigenSTL::vector_Vector3d posed_collision_points_;
345 EigenSTL::vector_Vector3d sphere_centers_;
346};
347
349{
350public:
352
353 PosedBodyPointDecomposition(const BodyDecompositionConstPtr& body_decomposition);
354
355 PosedBodyPointDecomposition(const BodyDecompositionConstPtr& body_decomposition, const Eigen::Isometry3d& pose);
356
357 PosedBodyPointDecomposition(const std::shared_ptr<const octomap::OcTree>& octree);
358
359 const EigenSTL::vector_Vector3d& getCollisionPoints() const
360 {
362 }
363 // the collision spheres, and the posed collision points
364 void updatePose(const Eigen::Isometry3d& linkTransform);
365
366protected:
367 BodyDecompositionConstPtr body_decomposition_;
368 EigenSTL::vector_Vector3d posed_collision_points_;
369};
370
372{
373public:
375
377 : logger_(moveit::getLogger("moveit.core.posed_body_sphere_decomposition_vector"))
378 {
379 }
380
381 const std::vector<CollisionSphere>& getCollisionSpheres() const
382 {
383 return collision_spheres_;
384 }
385
386 const EigenSTL::vector_Vector3d& getSphereCenters() const
387 {
388 return posed_collision_spheres_;
389 }
390
391 const std::vector<double>& getSphereRadii() const
392 {
393 return sphere_radii_;
394 }
395
396 void addToVector(PosedBodySphereDecompositionPtr& bd)
397 {
398 sphere_index_map_[decomp_vector_.size()] = collision_spheres_.size();
399 decomp_vector_.push_back(bd);
400 collision_spheres_.insert(collision_spheres_.end(), bd->getCollisionSpheres().begin(),
401 bd->getCollisionSpheres().end());
402 posed_collision_spheres_.insert(posed_collision_spheres_.end(), bd->getSphereCenters().begin(),
403 bd->getSphereCenters().end());
404 sphere_radii_.insert(sphere_radii_.end(), bd->getSphereRadii().begin(), bd->getSphereRadii().end());
405 }
406
407 unsigned int getSize() const
408 {
409 return decomp_vector_.size();
410 }
411
412 PosedBodySphereDecompositionConstPtr getPosedBodySphereDecomposition(unsigned int i) const
413 {
414 if (i >= decomp_vector_.size())
415 {
416 RCLCPP_INFO(logger_, "No body decomposition");
417 return empty_ptr_;
418 }
419 return decomp_vector_[i];
420 }
421
422 void updatePose(unsigned int ind, const Eigen::Isometry3d& pose)
423 {
424 if (ind >= decomp_vector_.size())
425 {
426 RCLCPP_WARN(logger_, "Can't update pose");
427 return;
428 }
429 decomp_vector_[ind]->updatePose(pose);
430 for (unsigned int i = 0; i < decomp_vector_[ind]->getSphereCenters().size(); ++i)
431 {
432 posed_collision_spheres_[sphere_index_map_[ind] + i] = decomp_vector_[ind]->getSphereCenters()[i];
433 }
434 }
435
436private:
437 rclcpp::Logger logger_;
438 PosedBodySphereDecompositionConstPtr empty_ptr_;
439 std::vector<PosedBodySphereDecompositionPtr> decomp_vector_;
440 std::vector<CollisionSphere> collision_spheres_;
441 EigenSTL::vector_Vector3d posed_collision_spheres_;
442 std::vector<double> sphere_radii_;
443 std::map<unsigned int, unsigned int> sphere_index_map_;
444};
445
447{
448public:
450
451 PosedBodyPointDecompositionVector() : logger_(moveit::getLogger("moveit.core.posed_body_point_decomposition_vector"))
452 {
453 }
454
455 EigenSTL::vector_Vector3d getCollisionPoints() const
456 {
457 EigenSTL::vector_Vector3d ret_points;
458 for (const PosedBodyPointDecompositionPtr& decomp : decomp_vector_)
459 {
460 ret_points.insert(ret_points.end(), decomp->getCollisionPoints().begin(), decomp->getCollisionPoints().end());
461 }
462 return ret_points;
463 }
464
465 void addToVector(PosedBodyPointDecompositionPtr& bd)
466 {
467 decomp_vector_.push_back(bd);
468 }
469
470 unsigned int getSize() const
471 {
472 return decomp_vector_.size();
473 }
474
475 PosedBodyPointDecompositionConstPtr getPosedBodyDecomposition(unsigned int i) const
476 {
477 if (i >= decomp_vector_.size())
478 {
479 RCLCPP_INFO(logger_, "No body decomposition");
480 return empty_ptr_;
481 }
482 return decomp_vector_[i];
483 }
484
485 void updatePose(unsigned int ind, const Eigen::Isometry3d& pose)
486 {
487 if (ind < decomp_vector_.size())
488 {
489 decomp_vector_[ind]->updatePose(pose);
490 }
491 else
492 {
493 RCLCPP_WARN(logger_, "Can't update pose");
494 return;
495 }
496 }
497
498protected:
499 rclcpp::Logger logger_;
500
501private:
502 PosedBodyPointDecompositionPtr empty_ptr_;
503 std::vector<PosedBodyPointDecompositionPtr> decomp_vector_;
504};
505
507{
509
510 std::string link_name;
512 double proximity;
513 unsigned int sphere_index;
514 unsigned int att_index;
515 Eigen::Vector3d closest_point;
516 Eigen::Vector3d closest_gradient;
517};
518
519bool doBoundingSpheresIntersect(const PosedBodySphereDecompositionConstPtr& p1,
520 const PosedBodySphereDecompositionConstPtr& p2);
521
522void getCollisionSphereMarkers(const std_msgs::msg::ColorRGBA& color, const std::string& frame_id,
523 const std::string& ns, const rclcpp::Duration& dur,
524 const std::vector<PosedBodySphereDecompositionPtr>& posed_decompositions,
525 visualization_msgs::msg::MarkerArray& arr);
526
527void getProximityGradientMarkers(const std::string& frame_id, const std::string& ns, const rclcpp::Duration& dur,
528 const std::vector<PosedBodySphereDecompositionPtr>& posed_decompositions,
529 const std::vector<PosedBodySphereDecompositionVectorPtr>& posed_vector_decompositions,
530 const std::vector<GradientInfo>& gradients, visualization_msgs::msg::MarkerArray& arr);
531
532void getCollisionMarkers(const std::string& frame_id, const std::string& ns, const rclcpp::Duration& dur,
533 const std::vector<PosedBodySphereDecompositionPtr>& posed_decompositions,
534 const std::vector<PosedBodySphereDecompositionVectorPtr>& posed_vector_decompositions,
535 const std::vector<GradientInfo>& gradients, visualization_msgs::msg::MarkerArray& arr);
536} // namespace collision_detection
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
#define MOVEIT_CLASS_FORWARD(C)
const EigenSTL::vector_Vector3d & getCollisionPoints() const
const bodies::BoundingSphere & getRelativeBoundingSphere() const
void init(const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &poses, double resolution, double padding)
const bodies::Body * getBody(unsigned int i) const
const std::vector< double > & getSphereRadii() const
const std::vector< CollisionSphere > & getCollisionSpheres() const
void replaceCollisionSpheres(const std::vector< CollisionSphere > &new_collision_spheres, const Eigen::Isometry3d &new_relative_cylinder_pose)
PosedBodyPointDecompositionConstPtr getPosedBodyDecomposition(unsigned int i) const
void updatePose(unsigned int ind, const Eigen::Isometry3d &pose)
void updatePose(const Eigen::Isometry3d &linkTransform)
const EigenSTL::vector_Vector3d & getCollisionPoints() const
void updatePose(unsigned int ind, const Eigen::Isometry3d &pose)
const std::vector< CollisionSphere > & getCollisionSpheres() const
PosedBodySphereDecompositionConstPtr getPosedBodySphereDecomposition(unsigned int i) const
const EigenSTL::vector_Vector3d & getCollisionPoints() const
void updatePose(const Eigen::Isometry3d &linkTransform)
const EigenSTL::vector_Vector3d & getSphereCenters() const
const std::vector< CollisionSphere > & getCollisionSpheres() const
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...
void updatePose(const Eigen::Isometry3d &transform)
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)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PosedDistanceField(const Eigen::Vector3d &size, const Eigen::Vector3d &origin, double resolution, double max_distance, bool propagate_negative_distances=false)
DistanceField is an abstract base class for computing distances from sets of 3D obstacle points....
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 gradient is computed a...
A DistanceField implementation that uses a vector propagation method. Distances propagate outward fro...
PropagationDistanceField(double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y, double origin_z, double max_distance, bool propagate_negative_distances=false)
Constructor that initializes entire distance field to empty - all cells will be assigned maximum dist...
void getProximityGradientMarkers(const std::string &frame_id, const std::string &ns, const rclcpp::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, const std::vector< PosedBodySphereDecompositionVectorPtr > &posed_vector_decompositions, const std::vector< GradientInfo > &gradients, visualization_msgs::msg::MarkerArray &arr)
std::vector< CollisionSphere > determineCollisionSpheres(const bodies::Body *body, Eigen::Isometry3d &relativeTransform)
void getCollisionMarkers(const std::string &frame_id, const std::string &ns, const rclcpp::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, const std::vector< PosedBodySphereDecompositionVectorPtr > &posed_vector_decompositions, const std::vector< GradientInfo > &gradients, visualization_msgs::msg::MarkerArray &arr)
void getCollisionSphereMarkers(const std_msgs::msg::ColorRGBA &color, const std::string &frame_id, const std::string &ns, const rclcpp::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, visualization_msgs::msg::MarkerArray &arr)
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)
bool doBoundingSpheresIntersect(const PosedBodySphereDecompositionConstPtr &p1, const PosedBodySphereDecompositionConstPtr &p2)
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)
Namespace for holding classes that generate distance fields.
Main namespace for MoveIt.
Definition exceptions.h:43
Definition world.h:49
CollisionSphere(const Eigen::Vector3d &rel, double radius)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d relative_vec_
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double closest_distance
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string link_name