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 namespace collision_detection
41 {
42 CollisionWorld::CollisionWorld() : world_(new World()), world_const_(world_)
43 {
44 }
45 
46 CollisionWorld::CollisionWorld(const WorldPtr& world) : world_(world), world_const_(world)
47 {
48 }
49 
50 CollisionWorld::CollisionWorld(const CollisionWorld& other, const WorldPtr& world) : world_(world), world_const_(world)
51 {
52 }
53 
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 robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const
64 {
65  robot.checkSelfCollision(req, res, state, acm);
66  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
67  checkRobotCollision(req, res, robot, state, acm);
68 }
69 
71  const robot_state::RobotState& state1, const robot_state::RobotState& state2) const
72 {
73  robot.checkSelfCollision(req, res, state1, state2);
74  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
75  checkRobotCollision(req, res, robot, state1, state2);
76 }
77 
79  const robot_state::RobotState& state1, const robot_state::RobotState& state2,
80  const AllowedCollisionMatrix& acm) const
81 {
82  robot.checkSelfCollision(req, res, state1, state2, acm);
83  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
84  checkRobotCollision(req, res, robot, state1, state2, acm);
85 }
86 
87 void CollisionWorld::setWorld(const WorldPtr& world)
88 {
89  world_ = world;
90  if (!world_)
91  world_.reset(new World());
92 
93  world_const_ = world;
94 }
95 
96 } // end of namespace collision_detection
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...
Generic interface to collision detection.
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: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...


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