moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_common_distance_field.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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 
44 
45 namespace collision_detection
46 {
49 
57 {
59 
62  {
64  for (unsigned int i = 0; i < gsr.link_body_decompositions_.size(); ++i)
65  {
66  if (gsr.link_body_decompositions_[i])
67  {
69  std::make_shared<PosedBodySphereDecomposition>(*gsr.link_body_decompositions_[i]);
70  }
71  }
72 
74 
76  for (unsigned int i = 0; i < gsr.attached_body_decompositions_.size(); ++i)
77  {
79  }
80  gradients_ = gsr.gradients_;
81  }
82 
84  DistanceFieldCacheEntryConstPtr dfce_;
85 
90  std::vector<PosedBodySphereDecompositionPtr> link_body_decompositions_;
91 
94  std::vector<PosedBodySphereDecompositionVectorPtr> attached_body_decompositions_;
95 
97  std::vector<PosedDistanceFieldPtr> link_distance_fields_;
98 
102  std::vector<GradientInfo> gradients_;
103 };
104 
112 {
114 
116  std::string group_name_;
118  moveit::core::RobotStatePtr state_;
123  std::vector<unsigned int> state_check_indices_;
128  std::vector<double> state_values_;
129  /* the acm used when generating this dfce. This dfce cannot be used to check
130  * collisions with a different acm. */
134  distance_field::DistanceFieldPtr distance_field_;
137  GroupStateRepresentationPtr pregenerated_group_state_representation_;
141  std::vector<std::string> link_names_;
143  std::vector<bool> link_has_geometry_;
149  std::vector<unsigned int> link_body_indices_;
152  std::vector<unsigned int> link_state_indices_;
154  std::vector<std::string> attached_body_names_;
157  std::vector<unsigned int> attached_body_link_state_indices_;
160  std::vector<bool> self_collision_enabled_;
166  std::vector<std::vector<bool>> intra_group_collision_enabled_;
167 };
168 
169 BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeConstPtr& shape, double resolution);
170 
171 PosedBodyPointDecompositionVectorPtr getCollisionObjectPointDecomposition(const collision_detection::World::Object& obj,
172  double resolution);
173 
174 PosedBodySphereDecompositionVectorPtr getAttachedBodySphereDecomposition(const moveit::core::AttachedBody* att,
175  double resolution);
176 
177 PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition(const moveit::core::AttachedBody* att,
178  double resolution);
179 
180 void getBodySphereVisualizationMarkers(const GroupStateRepresentationPtr& gsr, const std::string& reference_frame,
181  visualization_msgs::msg::MarkerArray& body_marker_array);
182 } // namespace collision_detection
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
PosedBodyPointDecompositionVectorPtr getCollisionObjectPointDecomposition(const collision_detection::World::Object &obj, double resolution)
void getBodySphereVisualizationMarkers(const GroupStateRepresentationPtr &gsr, const std::string &reference_frame, visualization_msgs::msg::MarkerArray &body_marker_array)
MOVEIT_STRUCT_FORWARD(CollisionGeometryData)
PosedBodySphereDecompositionVectorPtr getAttachedBodySphereDecomposition(const moveit::core::AttachedBody *att, double resolution)
BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeConstPtr &shape, double resolution)
PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition(const moveit::core::AttachedBody *att, double resolution)
collision_detection::AllowedCollisionMatrix acm_
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string group_name_
std::vector< std::vector< bool > > intra_group_collision_enabled_
std::vector< PosedBodySphereDecompositionVectorPtr > attached_body_decompositions_
GroupStateRepresentation(const GroupStateRepresentation &gsr)
std::vector< PosedBodySphereDecompositionPtr > link_body_decompositions_
std::vector< PosedDistanceFieldPtr > link_distance_fields_
A representation of an object.
Definition: world.h:79