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 #include <boost/thread/mutex.hpp>
45 
46 namespace collision_detection
47 {
50 class CollisionEnvHybrid : public collision_detection::CollisionEnvFCL
51 {
52 public:
53  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54 
55  CollisionEnvHybrid(const moveit::core::RobotModelConstPtr& robot_model,
56  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions =
57  std::map<std::string, std::vector<CollisionSphere>>(),
58  double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z,
59  const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0),
60  bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
61  double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
62  double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0,
63  double scale = 1.0);
64 
65  CollisionEnvHybrid(const moveit::core::RobotModelConstPtr& robot_model, const WorldPtr& world,
66  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions =
67  std::map<std::string, std::vector<CollisionSphere>>(),
68  double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z,
69  const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0),
70  bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
71  double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
72  double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0,
73  double scale = 1.0);
74 
75  CollisionEnvHybrid(const CollisionEnvHybrid& other, const WorldPtr& world);
76 
77  ~CollisionEnvHybrid() override
78  {
79  }
80 
81  void initializeRobotDistanceField(const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
82  double size_x, double size_y, double size_z, bool use_signed_distance_field,
83  double resolution, double collision_tolerance, double max_propogation_distance)
84  {
85  cenv_distance_->initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z),
86  Eigen::Vector3d(0, 0, 0), use_signed_distance_field, resolution, collision_tolerance,
87  max_propogation_distance);
88  }
89 
92  const moveit::core::RobotState& state) const;
93 
96  GroupStateRepresentationPtr& gsr) const;
97 
101 
105  GroupStateRepresentationPtr& gsr) const;
106  const CollisionEnvDistanceFieldConstPtr getCollisionRobotDistanceField() const
107  {
108  return cenv_distance_;
109  }
110 
111  void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res,
112  const moveit::core::RobotState& state) const;
113 
114  void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res,
115  const moveit::core::RobotState& state, GroupStateRepresentationPtr& gsr) const;
116 
117  void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res,
118  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm) const;
119 
120  void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res,
121  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm,
122  GroupStateRepresentationPtr& gsr) const;
123 
124  void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res,
125  const moveit::core::RobotState& state) const;
126 
127  void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res,
128  const moveit::core::RobotState& state, GroupStateRepresentationPtr& gsr) const;
129 
130  void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res,
131  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm) const;
132 
133  void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res,
134  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm,
135  GroupStateRepresentationPtr& gsr) const;
136 
137  void setWorld(const WorldPtr& world) override;
138 
139  void getCollisionGradients(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state,
140  const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const;
141 
143  const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const;
144 
145  const CollisionEnvDistanceFieldConstPtr getCollisionWorldDistanceField() const
146  {
147  return cenv_distance_;
148  }
149 
150 protected:
151  CollisionEnvDistanceFieldPtr cenv_distance_;
152 };
153 } // namespace collision_detection
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:83
collision_common_distance_field.h
collision_detection::DEFAULT_COLLISION_TOLERANCE
static const double DEFAULT_COLLISION_TOLERANCE
Definition: collision_env_distance_field.h:85
collision_distance_field_types.h
collision_detection::CollisionEnvHybrid::setWorld
void setWorld(const WorldPtr &world) override
Definition: collision_env_hybrid.cpp:197
collision_detection::DEFAULT_MAX_PROPOGATION_DISTANCE
static const double DEFAULT_MAX_PROPOGATION_DISTANCE
Definition: collision_env_distance_field.h:86
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
collision_env_distance_field.h
collision_detection::CollisionEnvHybrid::getCollisionWorldDistanceField
const CollisionEnvDistanceFieldConstPtr getCollisionWorldDistanceField() const
Definition: collision_env_hybrid.h:209
collision_detection::CollisionRequest
Representation of a collision checking request.
Definition: include/moveit/collision_detection/collision_common.h:179
collision_detection::DEFAULT_SIZE_X
static const double DEFAULT_SIZE_X
Definition: collision_env_distance_field.h:80
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::DEFAULT_SIZE_Z
static const double DEFAULT_SIZE_Z
Definition: collision_env_distance_field.h:82
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::DEFAULT_SIZE_Y
static const double DEFAULT_SIZE_Y
Definition: collision_env_distance_field.h:81
collision_detection::CollisionResult
Representation of a collision checking result.
Definition: include/moveit/collision_detection/collision_common.h:382
collision_detection::CollisionEnvHybrid::~CollisionEnvHybrid
~CollisionEnvHybrid() override
Definition: collision_env_hybrid.h:141
collision_detection::CollisionEnvHybrid::cenv_distance_
CollisionEnvDistanceFieldPtr cenv_distance_
Definition: collision_env_hybrid.h:215
collision_detection::CollisionEnvHybrid::getCollisionRobotDistanceField
const CollisionEnvDistanceFieldConstPtr getCollisionRobotDistanceField() const
Definition: collision_env_hybrid.h:170
collision_detection::CollisionEnvHybrid::initializeRobotDistanceField
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)
Definition: collision_env_hybrid.h:145
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
FCL implementation of the CollisionEnv.
Definition: collision_env_fcl.h:85
collision_env_fcl.h
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_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::DEFAULT_USE_SIGNED_DISTANCE_FIELD
static const bool DEFAULT_USE_SIGNED_DISTANCE_FIELD
Definition: collision_env_distance_field.h:83
fcl::Vector3d
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
collision_detection::DEFAULT_RESOLUTION
static const double DEFAULT_RESOLUTION
Definition: collision_env_distance_field.h:84
collision_detection
Definition: collision_detector_allocator_allvalid.h:42


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Nov 21 2024 03:23:41