collision_world_allvalid.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 
38 
40 {
41 }
42 
44 {
45 }
46 
48  : CollisionWorld(other, world)
49 {
50 }
51 
53  const CollisionRobot& robot,
54  const robot_state::RobotState& state) const
55 {
56  res.collision = false;
57  if (req.verbose)
58  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
59 }
60 
62  const CollisionRobot& robot,
63  const robot_state::RobotState& state,
64  const AllowedCollisionMatrix& acm) const
65 {
66  res.collision = false;
67  if (req.verbose)
68  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
69 }
70 
72  const CollisionRobot& robot,
73  const robot_state::RobotState& state1,
74  const robot_state::RobotState& state2) const
75 {
76  res.collision = false;
77  if (req.verbose)
78  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
79 }
80 
82  const CollisionRobot& robot,
83  const robot_state::RobotState& state1,
84  const robot_state::RobotState& state2,
85  const AllowedCollisionMatrix& acm) const
86 {
87  res.collision = false;
88  if (req.verbose)
89  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
90 }
91 
93  const CollisionWorld& other_world) const
94 {
95  res.collision = false;
96  if (req.verbose)
97  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
98 }
99 
101  const CollisionWorld& other_world,
102  const AllowedCollisionMatrix& acm) const
103 {
104  res.collision = false;
105  if (req.verbose)
106  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
107 }
108 
110  const robot_state::RobotState& state) const
111 {
112  return 0.0;
113 }
114 
116  const robot_state::RobotState& state,
117  const AllowedCollisionMatrix& acm) const
118 {
119  return 0.0;
120 }
121 
125  const moveit::core::RobotState& state) const
126 {
127  res.collision = false;
128 }
129 
131 {
132  return 0.0;
133 }
134 
136  const AllowedCollisionMatrix& acm) const
137 {
138  return 0.0;
139 }
140 
143  const collision_detection::CollisionWorld& world) const
144 {
145  res.collision = false;
146 }
147 
#define ROS_INFO_NAMED(name,...)
virtual double distanceWorld(const CollisionWorld &world) const
virtual double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state) const
bool collision
True if collision was found, false otherwise.
bool verbose
Flag indicating whether information about detected collisions should be reported. ...
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 checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const
Check whether a given set of objects is in collision with objects from another world. Any contacts are considered.
bool collision
Indicates if two objects were in collision.
Perform collision checking with the environment. The collision world maintains a representation of th...
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
Representation of a robot's state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:123


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