collision_env_hybrid.cpp
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, Jens Petit */
36 
39 
40 namespace collision_detection
41 {
42 namespace
43 {
44 static const std::string NAME = "HYBRID";
45 } // namespace
46 
48  const moveit::core::RobotModelConstPtr& robot_model,
49  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, double size_x, double size_y,
50  double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution,
51  double collision_tolerance, double max_propogation_distance, double padding, double scale)
52  : CollisionEnvFCL(robot_model)
53  , cenv_distance_(new collision_detection::CollisionEnvDistanceField(
54  robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, origin, use_signed_distance_field,
55  resolution, collision_tolerance, max_propogation_distance, padding, scale))
56 {
57 }
58 
60  const moveit::core::RobotModelConstPtr& robot_model, const WorldPtr& world,
61  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, double size_x, double size_y,
62  double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution,
63  double collision_tolerance, double max_propogation_distance, double padding, double scale)
64  : CollisionEnvFCL(robot_model, world, padding, scale)
65  , cenv_distance_(new collision_detection::CollisionEnvDistanceField(
66  robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, origin, use_signed_distance_field,
67  resolution, collision_tolerance, max_propogation_distance, padding, scale))
68 {
69 }
70 
71 CollisionEnvHybrid::CollisionEnvHybrid(const CollisionEnvHybrid& other, const WorldPtr& world)
72  : CollisionEnvFCL(other, world)
73  , cenv_distance_(new collision_detection::CollisionEnvDistanceField(*other.getCollisionWorldDistanceField(), world))
74 {
75 }
76 
79  const moveit::core::RobotState& state) const
80 {
81  cenv_distance_->checkSelfCollision(req, res, state);
82 }
83 
86  const moveit::core::RobotState& state,
87  GroupStateRepresentationPtr& gsr) const
88 {
89  cenv_distance_->checkSelfCollision(req, res, state, gsr);
90 }
91 
94  const moveit::core::RobotState& state,
96 {
97  cenv_distance_->checkSelfCollision(req, res, state, acm);
98 }
99 
102  const moveit::core::RobotState& state,
104  GroupStateRepresentationPtr& gsr) const
105 {
106  cenv_distance_->checkSelfCollision(req, res, state, acm, gsr);
107 }
108 
110  const moveit::core::RobotState& state) const
111 {
112  cenv_distance_->checkCollision(req, res, state);
113 }
114 
117  GroupStateRepresentationPtr& gsr) const
118 {
119  cenv_distance_->checkCollision(req, res, state, gsr);
120 }
121 
123  const moveit::core::RobotState& state,
124  const AllowedCollisionMatrix& acm) const
125 {
126  cenv_distance_->checkCollision(req, res, state, acm);
127 }
128 
130  const moveit::core::RobotState& state,
131  const AllowedCollisionMatrix& acm,
132  GroupStateRepresentationPtr& gsr) const
133 {
134  cenv_distance_->checkCollision(req, res, state, acm, gsr);
135 }
136 
138  const moveit::core::RobotState& state) const
139 {
140  cenv_distance_->checkRobotCollision(req, res, state);
141 }
142 
144  const moveit::core::RobotState& state,
145  GroupStateRepresentationPtr& gsr) const
146 {
147  cenv_distance_->checkRobotCollision(req, res, state, gsr);
148 }
149 
151  const moveit::core::RobotState& state,
152  const AllowedCollisionMatrix& acm) const
153 {
154  cenv_distance_->checkRobotCollision(req, res, state, acm);
155 }
156 
158  const moveit::core::RobotState& state,
159  const AllowedCollisionMatrix& acm,
160  GroupStateRepresentationPtr& gsr) const
161 {
162  cenv_distance_->checkRobotCollision(req, res, state, acm, gsr);
163 }
164 
165 void CollisionEnvHybrid::setWorld(const WorldPtr& world)
166 {
167  if (world == getWorld())
168  return;
169 
170  cenv_distance_->setWorld(world);
172 }
173 
176  GroupStateRepresentationPtr& gsr) const
177 {
178  cenv_distance_->getCollisionGradients(req, res, state, acm, gsr);
179 }
180 
183  GroupStateRepresentationPtr& gsr) const
184 {
185  cenv_distance_->getAllCollisions(req, res, state, acm, gsr);
186 }
187 
188 const std::string& CollisionDetectorAllocatorHybrid::getName() const
189 {
190  return NAME;
191 }
192 
193 } // namespace collision_detection
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:83
collision_detection::CollisionEnvHybrid::setWorld
void setWorld(const WorldPtr &world) override
Definition: collision_env_hybrid.cpp:197
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
collision_detection::CollisionRequest
Representation of a collision checking request.
Definition: include/moveit/collision_detection/collision_common.h:179
collision_detection::CollisionEnvHybrid::getAllCollisions
void getAllCollisions(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_hybrid.cpp:213
collision_detection::AllowedCollisionMatrix
Definition of a structure for the allowed collision matrix.
Definition: collision_matrix.h:112
collision_detection::NAME
static const std::string NAME
Definition: collision_env_fcl.cpp:81
collision_detection::CollisionEnvHybrid::CollisionEnvHybrid
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionEnvHybrid(const moveit::core::RobotModelConstPtr &robot_model, const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions=std::map< std::string, std::vector< CollisionSphere >>(), double size_x=DEFAULT_SIZE_X, double size_y=DEFAULT_SIZE_Y, double size_z=DEFAULT_SIZE_Z, const Eigen::Vector3d &origin=Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field=DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution=DEFAULT_RESOLUTION, double collision_tolerance=DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance=DEFAULT_MAX_PROPOGATION_DISTANCE, double padding=0.0, double scale=1.0)
Definition: collision_env_hybrid.cpp:79
collision_detection::CollisionResult
Representation of a collision checking result.
Definition: include/moveit/collision_detection/collision_common.h:382
collision_detection::CollisionEnvHybrid::cenv_distance_
CollisionEnvDistanceFieldPtr cenv_distance_
Definition: collision_env_hybrid.h:215
collision_env_hybrid.h
collision_detection::CollisionEnvHybrid::checkRobotCollisionDistanceField
void checkRobotCollisionDistanceField(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const
Definition: collision_env_hybrid.cpp:169
collision_detection::CollisionEnvFCL::setWorld
void setWorld(const WorldPtr &world) override
Definition: collision_env_fcl.cpp:433
collision_detection::CollisionDetectorAllocatorHybrid::getName
const std::string & getName() const override
Definition: collision_env_hybrid.cpp:220
collision_detection::CollisionEnvHybrid::checkSelfCollisionDistanceField
void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state) const
Definition: collision_env_hybrid.cpp:109
collision_detection::CollisionEnvHybrid::checkCollisionDistanceField
void checkCollisionDistanceField(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const
Definition: collision_env_hybrid.cpp:141
collision_detector_allocator_hybrid.h
collision_detection::CollisionEnvHybrid::getCollisionGradients
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_hybrid.cpp:206
collision_detection::CollisionEnv::getWorld
const WorldPtr & getWorld()
Definition: collision_env.h:267
fcl::Vector3d
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
collision_detection
Definition: collision_detector_allocator_allvalid.h:42


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