moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_env_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 #include <rclcpp/rclcpp.hpp>
45 #include <mutex>
46 
47 namespace collision_detection
48 {
49 static const double DEFAULT_SIZE_X = 3.0;
50 static const double DEFAULT_SIZE_Y = 3.0;
51 static const double DEFAULT_SIZE_Z = 4.0;
52 static const bool DEFAULT_USE_SIGNED_DISTANCE_FIELD = false;
53 static const double DEFAULT_RESOLUTION = .02;
54 static const double DEFAULT_COLLISION_TOLERANCE = 0.0;
55 static const double DEFAULT_MAX_PROPOGATION_DISTANCE = .25;
56 
57 MOVEIT_CLASS_FORWARD(CollisionEnvDistanceField); // Defines CollisionEnvDistanceFieldPtr, ConstPtr, WeakPtr... etc
58 
60 {
61 public:
63 
64  CollisionEnvDistanceField(const moveit::core::RobotModelConstPtr& robot_model,
65  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions =
66  std::map<std::string, std::vector<CollisionSphere>>(),
67  double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y,
68  double size_z = DEFAULT_SIZE_Z, const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0),
69  bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
70  double resolution = DEFAULT_RESOLUTION,
71  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  CollisionEnvDistanceField(const moveit::core::RobotModelConstPtr& robot_model, const WorldPtr& world,
76  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions =
77  std::map<std::string, std::vector<CollisionSphere>>(),
78  double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y,
79  double size_z = DEFAULT_SIZE_Z, const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0),
80  bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
81  double resolution = DEFAULT_RESOLUTION,
82  double collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
83  double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0,
84  double scale = 1.0);
85 
86  CollisionEnvDistanceField(const CollisionEnvDistanceField& other, const WorldPtr& world);
87 
88  void initialize(const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
89  const Eigen::Vector3d& size, const Eigen::Vector3d& origin, bool use_signed_distance_field,
90  double resolution, double collision_tolerance, double max_propogation_distance);
91 
93  const moveit::core::RobotState& state) const override;
94 
96  const moveit::core::RobotState& state, GroupStateRepresentationPtr& gsr) const;
97 
99  const moveit::core::RobotState& state,
100  const collision_detection::AllowedCollisionMatrix& acm) const override;
101 
104  GroupStateRepresentationPtr& gsr) const;
105 
107  visualization_msgs::msg::MarkerArray& model_markers) const;
108 
109  virtual double distanceSelf(const moveit::core::RobotState& /* state */) const
110  {
111  return 0.0;
112  }
113 
114  virtual double distanceSelf(const moveit::core::RobotState& /* state */,
115  const collision_detection::AllowedCollisionMatrix& /* acm */) const
116  {
117  return 0.0;
118  }
119 
120  void distanceSelf(const DistanceRequest& /* req */, DistanceResult& /* res */,
121  const moveit::core::RobotState& /* state */) const override
122  {
123  RCLCPP_ERROR(LOGGER, "Not implemented");
124  }
125 
126  DistanceFieldCacheEntryConstPtr getLastDistanceFieldEntry() const
127  {
129  }
130 
131  // void getSelfCollisionsGradients(const collision_detection::CollisionRequest
132  // &req,
133  // collision_detection::CollisionResult &res,
134  // const moveit::core::RobotState &state,
135  // const
136  // collision_detection::AllowedCollisionMatrix
137  // &acm) const;
138 
141  {
142  std::map<std::string, std::vector<PosedBodyPointDecompositionPtr>> posed_body_point_decompositions_;
143  distance_field::DistanceFieldPtr distance_field_;
144  };
145 
146  ~CollisionEnvDistanceField() override;
147 
148  void checkCollision(const CollisionRequest& req, CollisionResult& res,
149  const moveit::core::RobotState& state) const override;
150 
151  virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state,
152  GroupStateRepresentationPtr& gsr) const;
153 
154  void checkCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state,
155  const AllowedCollisionMatrix& acm) const override;
156 
157  virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state,
158  const AllowedCollisionMatrix& acm, GroupStateRepresentationPtr& gsr) const;
159 
161  const moveit::core::RobotState& state) const override;
162 
163  virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res,
164  const moveit::core::RobotState& state, GroupStateRepresentationPtr& gsr) const;
165 
167  const AllowedCollisionMatrix& acm) const override;
168 
169  virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res,
170  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm,
171  GroupStateRepresentationPtr& gsr) const;
172 
174  const moveit::core::RobotState& state2, const AllowedCollisionMatrix& acm) const override;
175 
177  const moveit::core::RobotState& state2) const override;
178 
179  virtual double distanceRobot(const moveit::core::RobotState& state, bool verbose = false) const
180  {
181  (void)state;
182  (void)verbose;
183  return 0.0;
184  }
185 
186  virtual double distanceRobot(const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm,
187  bool verbose = false) const
188  {
189  (void)state;
190  (void)acm;
191  (void)verbose;
192  return 0.0;
193  }
194 
195  void distanceRobot(const DistanceRequest& /* req */, DistanceResult& /* res */,
196  const moveit::core::RobotState& /* state */) const override
197  {
198  RCLCPP_ERROR(LOGGER, "Not implemented");
199  }
200 
201  void setWorld(const WorldPtr& world) override;
202 
203  distance_field::DistanceFieldConstPtr getDistanceField() const
204  {
205  return distance_field_cache_entry_->distance_field_;
206  }
207 
208  collision_detection::GroupStateRepresentationConstPtr getLastGroupStateRepresentation() const
209  {
210  return last_gsr_;
211  }
212 
214  const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const;
215 
217  const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const;
218 
219 protected:
220  bool getSelfProximityGradients(GroupStateRepresentationPtr& gsr) const;
221 
222  bool getIntraGroupProximityGradients(GroupStateRepresentationPtr& gsr) const;
223 
225  GroupStateRepresentationPtr& gsr) const;
226 
228  collision_detection::CollisionResult& res, GroupStateRepresentationPtr& gsr) const;
229 
233  GroupStateRepresentationPtr& gsr) const;
234 
236  GroupStateRepresentationPtr& gsr) const;
237 
238  void generateCollisionCheckingStructures(const std::string& group_name, const moveit::core::RobotState& state,
240  GroupStateRepresentationPtr& gsr, bool generate_distance_field) const;
241 
242  DistanceFieldCacheEntryConstPtr
243  getDistanceFieldCacheEntry(const std::string& group_name, const moveit::core::RobotState& state,
245 
246  DistanceFieldCacheEntryPtr generateDistanceFieldCacheEntry(const std::string& group_name,
247  const moveit::core::RobotState& state,
249  bool generate_distance_field) const;
250 
251  void addLinkBodyDecompositions(double resolution);
252 
253  void addLinkBodyDecompositions(double resolution,
254  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions);
255 
256  PosedBodySphereDecompositionPtr getPosedLinkBodySphereDecomposition(const moveit::core::LinkModel* ls,
257  unsigned int ind) const;
258 
259  PosedBodyPointDecompositionPtr getPosedLinkBodyPointDecomposition(const moveit::core::LinkModel* ls) const;
260 
261  void getGroupStateRepresentation(const DistanceFieldCacheEntryConstPtr& dfce, const moveit::core::RobotState& state,
262  GroupStateRepresentationPtr& gsr) const;
263 
264  bool compareCacheEntryToState(const DistanceFieldCacheEntryConstPtr& dfce,
265  const moveit::core::RobotState& state) const;
266 
267  bool compareCacheEntryToAllowedCollisionMatrix(const DistanceFieldCacheEntryConstPtr& dfce,
269 
270  void updatedPaddingOrScaling(const std::vector<std::string>& /*links*/) override{};
271 
272  DistanceFieldCacheEntryWorldPtr generateDistanceFieldCacheEntryWorld();
273 
274  void updateDistanceObject(const std::string& id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr& dfce,
275  EigenSTL::vector_Vector3d& add_points, EigenSTL::vector_Vector3d& subtract_points);
276 
278  const distance_field::DistanceFieldConstPtr& env_distance_field,
279  GroupStateRepresentationPtr& gsr) const;
280 
281  bool getEnvironmentProximityGradients(const distance_field::DistanceFieldConstPtr& env_distance_field,
282  GroupStateRepresentationPtr& gsr) const;
283 
285 
286  // Logger
287  static const rclcpp::Logger LOGGER;
288 
292  double resolution_;
295 
296  std::vector<BodyDecompositionConstPtr> link_body_decomposition_vector_;
297  std::map<std::string, unsigned int> link_body_decomposition_index_map_;
298 
299  mutable std::mutex update_cache_lock_;
300  DistanceFieldCacheEntryPtr distance_field_cache_entry_;
301  std::map<std::string, std::map<std::string, bool>> in_group_update_map_;
302  std::map<std::string, GroupStateRepresentationPtr> pregenerated_group_state_representation_map_;
303 
304  planning_scene::PlanningScenePtr planning_scene_;
305 
306  mutable std::mutex update_cache_lock_world_;
307  DistanceFieldCacheEntryWorldPtr distance_field_cache_entry_world_;
308  GroupStateRepresentationPtr last_gsr_;
310 };
311 } // 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...
virtual double distanceSelf(const moveit::core::RobotState &) const
DistanceFieldCacheEntryWorldPtr distance_field_cache_entry_world_
void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
DistanceFieldCacheEntryConstPtr getDistanceFieldCacheEntry(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm) const
DistanceFieldCacheEntryPtr generateDistanceFieldCacheEntry(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, bool generate_distance_field) const
std::map< std::string, std::map< std::string, bool > > in_group_update_map_
void initialize(const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions, const Eigen::Vector3d &size, const Eigen::Vector3d &origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionEnvDistanceField(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)
DistanceFieldCacheEntryWorldPtr generateDistanceFieldCacheEntryWorld()
bool getSelfCollisions(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
void distanceRobot(const DistanceRequest &, DistanceResult &, const moveit::core::RobotState &) const override
Compute the distance between a robot and the world.
DistanceFieldCacheEntryConstPtr getLastDistanceFieldEntry() const
virtual double distanceRobot(const moveit::core::RobotState &state, bool verbose=false) const
bool compareCacheEntryToAllowedCollisionMatrix(const DistanceFieldCacheEntryConstPtr &dfce, const collision_detection::AllowedCollisionMatrix &acm) const
std::map< std::string, unsigned int > link_body_decomposition_index_map_
bool getIntraGroupCollisions(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
void checkSelfCollisionHelper(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
void generateCollisionCheckingStructures(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr, bool generate_distance_field) const
bool compareCacheEntryToState(const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state) const
std::vector< BodyDecompositionConstPtr > link_body_decomposition_vector_
bool getEnvironmentProximityGradients(const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
std::map< std::string, GroupStateRepresentationPtr > pregenerated_group_state_representation_map_
bool getSelfProximityGradients(GroupStateRepresentationPtr &gsr) const
bool getEnvironmentCollisions(const CollisionRequest &req, CollisionResult &res, const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
void checkCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check whether the robot model is in collision with itself or the world at a particular state....
PosedBodySphereDecompositionPtr getPosedLinkBodySphereDecomposition(const moveit::core::LinkModel *ls, unsigned int ind) const
void updateGroupStateRepresentationState(const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
bool getIntraGroupProximityGradients(GroupStateRepresentationPtr &gsr) const
void updateDistanceObject(const std::string &id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr &dfce, EigenSTL::vector_Vector3d &add_points, EigenSTL::vector_Vector3d &subtract_points)
void getAllCollisions(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
PosedBodyPointDecompositionPtr getPosedLinkBodyPointDecomposition(const moveit::core::LinkModel *ls) const
virtual double distanceRobot(const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const
void distanceSelf(const DistanceRequest &, DistanceResult &, const moveit::core::RobotState &) const override
The distance to self-collision given the robot is at state state.
void notifyObjectChange(const ObjectConstPtr &obj, World::Action action)
void updatedPaddingOrScaling(const std::vector< std::string > &) override
When the scale or padding is changed for a set of links by any of the functions in this class,...
void createCollisionModelMarker(const moveit::core::RobotState &state, visualization_msgs::msg::MarkerArray &model_markers) const
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state) const override
Check for robot self collision. Any collision between any pair of links is checked for,...
MOVEIT_STRUCT_FORWARD(DistanceFieldCacheEntryWorld)
collision_detection::GroupStateRepresentationConstPtr getLastGroupStateRepresentation() const
void getGroupStateRepresentation(const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
distance_field::DistanceFieldConstPtr getDistanceField() const
virtual double distanceSelf(const moveit::core::RobotState &, const collision_detection::AllowedCollisionMatrix &) const
Provides the interface to the individual collision checking libraries.
Definition: collision_env.h:52
World::ObjectConstPtr ObjectConstPtr
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Definition: world.h:265
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
std::map< std::string, std::vector< PosedBodyPointDecompositionPtr > > posed_body_point_decompositions_
Representation of a collision checking request.
Representation of a collision checking result.
Representation of a distance-reporting request.
Result of a distance request.