collision_world.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, 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 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: Ioan Sucan, Sachin Chitta */
36 
37 #ifndef MOVEIT_COLLISION_DETECTION_COLLISION_WORLD_
38 #define MOVEIT_COLLISION_DETECTION_COLLISION_WORLD_
39 
40 #include <boost/utility.hpp>
41 
46 
48 namespace collision_detection
49 {
50 MOVEIT_CLASS_FORWARD(CollisionWorld);
51 
55 class CollisionWorld : private boost::noncopyable
56 {
57 public:
59 
60  explicit CollisionWorld(const WorldPtr& world);
61 
64  CollisionWorld(const CollisionWorld& other, const WorldPtr& world);
65 
66  virtual ~CollisionWorld()
67  {
68  }
69 
70  /**********************************************************************/
71  /* Collision Checking Routines */
72  /**********************************************************************/
73 
79  virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
80  const robot_state::RobotState& state) const;
81 
88  virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
89  const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const;
90 
98  virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
99  const robot_state::RobotState& state1, const robot_state::RobotState& state2) const;
100 
109  virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
110  const robot_state::RobotState& state1, const robot_state::RobotState& state2,
111  const AllowedCollisionMatrix& acm) const;
112 
120  virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
121  const robot_state::RobotState& state) const = 0;
122 
130  virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
131  const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const = 0;
132 
141  virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
142  const robot_state::RobotState& state1,
143  const robot_state::RobotState& state2) const = 0;
144 
154  virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
155  const robot_state::RobotState& state1, const robot_state::RobotState& state2,
156  const AllowedCollisionMatrix& acm) const = 0;
157 
164  virtual void checkWorldCollision(const CollisionRequest& req, CollisionResult& res,
165  const CollisionWorld& other_world) const = 0;
166 
173  virtual void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, const CollisionWorld& other_world,
174  const AllowedCollisionMatrix& acm) const = 0;
175 
180  inline double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state,
181  bool verbose = false) const
182  {
183  DistanceRequest req;
184  DistanceResult res;
185 
186  req.verbose = verbose;
187  req.enableGroup(robot.getRobotModel());
188 
189  distanceRobot(req, res, robot, state);
190  return res.minimum_distance.distance;
191  }
192 
199  inline double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state,
200  const AllowedCollisionMatrix& acm, bool verbose = false) const
201  {
202  DistanceRequest req;
203  DistanceResult res;
204 
205  req.acm = &acm;
206  req.verbose = verbose;
207  req.enableGroup(robot.getRobotModel());
208 
209  distanceRobot(req, res, robot, state);
210  return res.minimum_distance.distance;
211  }
212 
218  virtual void distanceRobot(const DistanceRequest& req, DistanceResult& res, const CollisionRobot& robot,
219  const robot_state::RobotState& state) const = 0;
220 
223  inline double distanceWorld(const CollisionWorld& world, bool verbose = false) const
224  {
225  DistanceRequest req;
226  DistanceResult res;
227 
228  req.verbose = verbose;
229  distanceWorld(req, res, world);
230 
231  return res.minimum_distance.distance;
232  }
233 
237  inline double distanceWorld(const CollisionWorld& world, const AllowedCollisionMatrix& acm,
238  bool verbose = false) const
239  {
240  DistanceRequest req;
241  DistanceResult res;
242 
243  req.acm = &acm;
244  req.verbose = verbose;
245  distanceWorld(req, res, world);
246 
247  return res.minimum_distance.distance;
248  }
249 
254  virtual void distanceWorld(const DistanceRequest& req, DistanceResult& res, const CollisionWorld& world) const = 0;
255 
259  virtual void setWorld(const WorldPtr& world);
260 
262  const WorldPtr& getWorld()
263  {
264  return world_;
265  }
266 
268  const WorldConstPtr& getWorld() const
269  {
270  return world_const_;
271  }
272 
273  typedef World::ObjectPtr ObjectPtr;
274  typedef World::ObjectConstPtr ObjectConstPtr;
275 
276 private:
277  WorldPtr world_; // The world. Always valid. Never NULL.
278  WorldConstPtr world_const_; // always same as world_
279 };
280 }
281 
282 #endif
virtual void checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const =0
Check whether a given set of objects is in collision with objects from another world. Any contacts are considered.
const WorldConstPtr & getWorld() const
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
const robot_model::RobotModelConstPtr & getRobotModel() const
The kinematic model corresponding to this collision model.
Generic interface to collision detection.
void enableGroup(const robot_model::RobotModelConstPtr &kmodel)
Compute active_components_only_ based on req_.
double distanceWorld(const CollisionWorld &world, bool verbose=false) const
The shortest distance to another world instance (world)
World::ObjectConstPtr ObjectConstPtr
bool verbose
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const =0
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
This class represents a collision model of the robot and can be used for self collision checks (to ch...
double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state, bool verbose=false) const
Compute the shortest distance between a robot and the world.
double distance
The distance between two objects. If two objects are in collision, distance <= 0. ...
virtual void setWorld(const WorldPtr &world)
Perform collision checking with the environment. The collision world maintains a representation of th...
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:123
virtual void checkCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
Check whether the robot model is in collision with itself or the world at a particular state...
double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const
Compute the shortest distance between a robot and the world.
double distanceWorld(const CollisionWorld &world, const AllowedCollisionMatrix &acm, bool verbose=false) const
The shortest distance to another world instance (world), ignoring the distances between world element...


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:33