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 {
47 MOVEIT_STRUCT_FORWARD(GroupStateRepresentation);
48 MOVEIT_STRUCT_FORWARD(DistanceFieldCacheEntry);
49 
56 struct GroupStateRepresentation
57 {
58  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
59 
62  {
63  link_body_decompositions_.resize(gsr.link_body_decompositions_.size());
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 
73  link_distance_fields_.assign(gsr.link_distance_fields_.begin(), gsr.link_distance_fields_.end());
74 
75  attached_body_decompositions_.resize(gsr.attached_body_decompositions_.size());
76  for (unsigned int i = 0; i < gsr.attached_body_decompositions_.size(); i++)
77  {
78  (*attached_body_decompositions_[i]) = (*gsr.attached_body_decompositions_[i]);
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 
111 struct DistanceFieldCacheEntry
112 {
113  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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::MarkerArray& body_marker_array);
182 } // namespace collision_detection
collision_detection::DistanceFieldCacheEntry::link_has_geometry_
std::vector< bool > link_has_geometry_
Definition: collision_common_distance_field.h:175
collision_detection::DistanceFieldCacheEntry::group_name_
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string group_name_
Definition: collision_common_distance_field.h:148
collision_detection::DistanceFieldCacheEntry::state_
moveit::core::RobotStatePtr state_
Definition: collision_common_distance_field.h:150
collision_detection::GroupStateRepresentation::dfce_
DistanceFieldCacheEntryConstPtr dfce_
Definition: collision_common_distance_field.h:116
collision_distance_field_types.h
collision_detection::DistanceFieldCacheEntry::pregenerated_group_state_representation_
GroupStateRepresentationPtr pregenerated_group_state_representation_
Definition: collision_common_distance_field.h:169
collision_detection::DistanceFieldCacheEntry::state_check_indices_
std::vector< unsigned int > state_check_indices_
Definition: collision_common_distance_field.h:155
collision_detection::getBodySphereVisualizationMarkers
void getBodySphereVisualizationMarkers(const GroupStateRepresentationPtr &gsr, const std::string &reference_frame, visualization_msgs::MarkerArray &body_marker_array)
collision_detection::DistanceFieldCacheEntry::intra_group_collision_enabled_
std::vector< std::vector< bool > > intra_group_collision_enabled_
Definition: collision_common_distance_field.h:198
collision_detection::GroupStateRepresentation::link_distance_fields_
std::vector< PosedDistanceFieldPtr > link_distance_fields_
Definition: collision_common_distance_field.h:129
collision_detection::DistanceFieldCacheEntry::distance_field_
distance_field::DistanceFieldPtr distance_field_
Definition: collision_common_distance_field.h:166
class_forward.h
collision_detection::GroupStateRepresentation::link_body_decompositions_
std::vector< PosedBodySphereDecompositionPtr > link_body_decompositions_
Definition: collision_common_distance_field.h:122
collision_detection::DistanceFieldCacheEntry::link_state_indices_
std::vector< unsigned int > link_state_indices_
Definition: collision_common_distance_field.h:184
collision_detection::getAttachedBodyPointDecomposition
PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition(const moveit::core::AttachedBody *att, double resolution)
Definition: collision_common_distance_field.cpp:149
collision_detection::DistanceFieldCacheEntry::attached_body_names_
std::vector< std::string > attached_body_names_
Definition: collision_common_distance_field.h:186
moveit::core::AttachedBody
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:121
collision_common.h
collision_detection::AllowedCollisionMatrix
Definition of a structure for the allowed collision matrix.
Definition: collision_matrix.h:112
collision_detection::GroupStateRepresentation::gradients_
std::vector< GradientInfo > gradients_
Definition: collision_common_distance_field.h:134
collision_detection::DistanceFieldCacheEntry::acm_
collision_detection::AllowedCollisionMatrix acm_
Definition: collision_common_distance_field.h:163
collision_env.h
collision_detection::DistanceFieldCacheEntry::link_body_indices_
std::vector< unsigned int > link_body_indices_
Definition: collision_common_distance_field.h:181
collision_detection::getBodyDecompositionCacheEntry
BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeConstPtr &shape, double resolution)
Definition: collision_common_distance_field.cpp:97
collision_detection::DistanceFieldCacheEntry::self_collision_enabled_
std::vector< bool > self_collision_enabled_
Definition: collision_common_distance_field.h:192
collision_detection::World::Object
A representation of an object.
Definition: world.h:79
collision_detection::DistanceFieldCacheEntry::link_names_
std::vector< std::string > link_names_
Definition: collision_common_distance_field.h:173
collision_detection::DistanceFieldCacheEntry::attached_body_link_state_indices_
std::vector< unsigned int > attached_body_link_state_indices_
Definition: collision_common_distance_field.h:189
collision_detection::GroupStateRepresentation::attached_body_decompositions_
std::vector< PosedBodySphereDecompositionVectorPtr > attached_body_decompositions_
Definition: collision_common_distance_field.h:126
collision_detection::DistanceFieldCacheEntry::state_values_
std::vector< double > state_values_
Definition: collision_common_distance_field.h:160
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
collision_detection::GroupStateRepresentation::GroupStateRepresentation
EIGEN_MAKE_ALIGNED_OPERATOR_NEW GroupStateRepresentation()
Definition: collision_common_distance_field.h:92
collision_detection::getAttachedBodySphereDecomposition
PosedBodySphereDecompositionVectorPtr getAttachedBodySphereDecomposition(const moveit::core::AttachedBody *att, double resolution)
Definition: collision_common_distance_field.cpp:135
collision_detection::getCollisionObjectPointDecomposition
PosedBodyPointDecompositionVectorPtr getCollisionObjectPointDecomposition(const collision_detection::World::Object &obj, double resolution)
Definition: collision_common_distance_field.cpp:121
robot_state.h
collision_detection::MOVEIT_STRUCT_FORWARD
MOVEIT_STRUCT_FORWARD(CollisionGeometryData)
collision_detection
Definition: collision_detector_allocator_allvalid.h:42


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14