moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_env_hybrid.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, Jens Petit */
36 
37 #pragma once
38 
43 
44 namespace collision_detection
45 {
49 {
50 public:
52 
53  CollisionEnvHybrid(const moveit::core::RobotModelConstPtr& robot_model,
54  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions =
55  std::map<std::string, std::vector<CollisionSphere>>(),
56  double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z,
57  const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0),
58  bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
59  double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
60  double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0,
61  double scale = 1.0);
62 
63  CollisionEnvHybrid(const moveit::core::RobotModelConstPtr& robot_model, const WorldPtr& world,
64  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions =
65  std::map<std::string, std::vector<CollisionSphere>>(),
66  double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z,
67  const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0),
68  bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
69  double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
70  double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0,
71  double scale = 1.0);
72 
73  CollisionEnvHybrid(const CollisionEnvHybrid& other, const WorldPtr& world);
74 
76  {
77  }
78 
79  void initializeRobotDistanceField(const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
80  double size_x, double size_y, double size_z, bool use_signed_distance_field,
81  double resolution, double collision_tolerance, double max_propogation_distance)
82  {
83  cenv_distance_->initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z),
84  Eigen::Vector3d(0, 0, 0), use_signed_distance_field, resolution, collision_tolerance,
85  max_propogation_distance);
86  }
87 
90  const moveit::core::RobotState& state) const;
91 
94  GroupStateRepresentationPtr& gsr) const;
95 
99 
103  GroupStateRepresentationPtr& gsr) const;
104  const CollisionEnvDistanceFieldConstPtr getCollisionRobotDistanceField() const
105  {
106  return cenv_distance_;
107  }
108 
110  const moveit::core::RobotState& state) const;
111 
113  const moveit::core::RobotState& state, GroupStateRepresentationPtr& gsr) const;
114 
116  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm) const;
117 
119  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm,
120  GroupStateRepresentationPtr& gsr) const;
121 
123  const moveit::core::RobotState& state) const;
124 
126  const moveit::core::RobotState& state, GroupStateRepresentationPtr& gsr) const;
127 
129  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm) const;
130 
132  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm,
133  GroupStateRepresentationPtr& gsr) const;
134 
135  void setWorld(const WorldPtr& world) override;
136 
138  const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const;
139 
141  const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const;
142 
143  const CollisionEnvDistanceFieldConstPtr getCollisionWorldDistanceField() const
144  {
145  return cenv_distance_;
146  }
147 
148 protected:
149  CollisionEnvDistanceFieldPtr cenv_distance_;
150 };
151 } // 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...
FCL implementation of the CollisionEnv.
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
void initializeRobotDistanceField(const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions, double size_x, double size_y, double size_z, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance)
CollisionEnvDistanceFieldPtr cenv_distance_
void setWorld(const WorldPtr &world) override
const CollisionEnvDistanceFieldConstPtr getCollisionWorldDistanceField() const
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)
const CollisionEnvDistanceFieldConstPtr getCollisionRobotDistanceField() const
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.