moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 {
43 
45  const moveit::core::RobotModelConstPtr& robot_model,
46  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, double size_x, double size_y,
47  double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution,
48  double collision_tolerance, double max_propogation_distance, double padding, double scale)
49  : CollisionEnvFCL(robot_model)
50  , cenv_distance_(std::make_shared<collision_detection::CollisionEnvDistanceField>(
51  robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, origin, use_signed_distance_field,
52  resolution, collision_tolerance, max_propogation_distance, padding, scale))
53 {
54 }
55 
57  const moveit::core::RobotModelConstPtr& robot_model, const WorldPtr& world,
58  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, double size_x, double size_y,
59  double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution,
60  double collision_tolerance, double max_propogation_distance, double padding, double scale)
61  : CollisionEnvFCL(robot_model, world, padding, scale)
62  , cenv_distance_(std::make_shared<collision_detection::CollisionEnvDistanceField>(
63  robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, origin, use_signed_distance_field,
64  resolution, collision_tolerance, max_propogation_distance, padding, scale))
65 {
66 }
67 
68 CollisionEnvHybrid::CollisionEnvHybrid(const CollisionEnvHybrid& other, const WorldPtr& world)
69  : CollisionEnvFCL(other, world)
70  , cenv_distance_(std::make_shared<collision_detection::CollisionEnvDistanceField>(
71  *other.getCollisionWorldDistanceField(), world))
72 {
73 }
74 
77  const moveit::core::RobotState& state) const
78 {
79  cenv_distance_->checkSelfCollision(req, res, state);
80 }
81 
84  const moveit::core::RobotState& state,
85  GroupStateRepresentationPtr& gsr) const
86 {
87  cenv_distance_->checkSelfCollision(req, res, state, gsr);
88 }
89 
92  const moveit::core::RobotState& state,
94 {
95  cenv_distance_->checkSelfCollision(req, res, state, acm);
96 }
97 
100  const moveit::core::RobotState& state,
102  GroupStateRepresentationPtr& gsr) const
103 {
104  cenv_distance_->checkSelfCollision(req, res, state, acm, gsr);
105 }
106 
108  const moveit::core::RobotState& state) const
109 {
110  cenv_distance_->checkCollision(req, res, state);
111 }
112 
114  const moveit::core::RobotState& state,
115  GroupStateRepresentationPtr& gsr) const
116 {
117  cenv_distance_->checkCollision(req, res, state, gsr);
118 }
119 
121  const moveit::core::RobotState& state,
122  const AllowedCollisionMatrix& acm) const
123 {
124  cenv_distance_->checkCollision(req, res, state, acm);
125 }
126 
128  const moveit::core::RobotState& state,
129  const AllowedCollisionMatrix& acm,
130  GroupStateRepresentationPtr& gsr) const
131 {
132  cenv_distance_->checkCollision(req, res, state, acm, gsr);
133 }
134 
136  const moveit::core::RobotState& state) const
137 {
138  cenv_distance_->checkRobotCollision(req, res, state);
139 }
140 
142  const moveit::core::RobotState& state,
143  GroupStateRepresentationPtr& gsr) const
144 {
145  cenv_distance_->checkRobotCollision(req, res, state, gsr);
146 }
147 
149  const moveit::core::RobotState& state,
150  const AllowedCollisionMatrix& acm) const
151 {
152  cenv_distance_->checkRobotCollision(req, res, state, acm);
153 }
154 
156  const moveit::core::RobotState& state,
157  const AllowedCollisionMatrix& acm,
158  GroupStateRepresentationPtr& gsr) const
159 {
160  cenv_distance_->checkRobotCollision(req, res, state, acm, gsr);
161 }
162 
163 void CollisionEnvHybrid::setWorld(const WorldPtr& world)
164 {
165  if (world == getWorld())
166  return;
167 
168  cenv_distance_->setWorld(world);
170 }
171 
173  const moveit::core::RobotState& state, const AllowedCollisionMatrix* acm,
174  GroupStateRepresentationPtr& gsr) const
175 {
176  cenv_distance_->getCollisionGradients(req, res, state, acm, gsr);
177 }
178 
180  const moveit::core::RobotState& state, const AllowedCollisionMatrix* acm,
181  GroupStateRepresentationPtr& gsr) const
182 {
183  cenv_distance_->getAllCollisions(req, res, state, acm, gsr);
184 }
185 } // namespace collision_detection
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
FCL implementation of the CollisionEnv.
void setWorld(const WorldPtr &world) override
This hybrid collision environment combines FCL and a distance field. Both can be used to calculate co...
void getAllCollisions(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
void checkRobotCollisionDistanceField(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const
void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state) const
CollisionEnvDistanceFieldPtr cenv_distance_
void setWorld(const WorldPtr &world) override
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)
void checkCollisionDistanceField(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
Representation of a collision checking request.
Representation of a collision checking result.