collision_world.cpp
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 */
36 
39 
40 collision_detection::CollisionWorld::CollisionWorld() : world_(new World()), world_const_(world_)
41 {
42 }
43 
45 {
46 }
47 
49  : world_(world), world_const_(world)
50 {
51 }
52 
54  const CollisionRobot& robot,
55  const robot_state::RobotState& state) const
56 {
57  robot.checkSelfCollision(req, res, state);
58  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
59  checkRobotCollision(req, res, robot, state);
60 }
61 
63  const CollisionRobot& robot,
64  const robot_state::RobotState& state,
65  const AllowedCollisionMatrix& acm) const
66 {
67  robot.checkSelfCollision(req, res, state, acm);
68  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
69  checkRobotCollision(req, res, robot, state, acm);
70 }
71 
73  const CollisionRobot& robot,
74  const robot_state::RobotState& state1,
75  const robot_state::RobotState& state2) const
76 {
77  robot.checkSelfCollision(req, res, state1, state2);
78  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
79  checkRobotCollision(req, res, robot, state1, state2);
80 }
81 
83  const CollisionRobot& robot,
84  const robot_state::RobotState& state1,
85  const robot_state::RobotState& state2,
86  const AllowedCollisionMatrix& acm) const
87 {
88  robot.checkSelfCollision(req, res, state1, state2, acm);
89  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
90  checkRobotCollision(req, res, robot, state1, state2, acm);
91 }
92 
94 {
95  world_ = world;
96  if (!world_)
97  world_.reset(new World());
98 
99  world_const_ = world;
100 }
virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const =0
Check for self collision. Any collision between any pair of links is checked for, NO collisions are i...
Maintain a representation of the environment.
Definition: world.h:60
ContactMap contacts
A map returning the pairs of ids of the bodies in contact, plus information about the contacts themse...
bool collision
True if collision was found, false otherwise.
std::size_t max_contacts
Overall maximum number of contacts to compute.
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...
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:82
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...


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Jan 21 2018 03:54:28