collision_robot_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, Jia Pan */
36 
38 
39 collision_detection::CollisionRobotAllValid::CollisionRobotAllValid(const robot_model::RobotModelConstPtr& kmodel,
40  double padding, double scale)
41  : CollisionRobot(kmodel, padding, scale)
42 {
43 }
44 
46 {
47 }
48 
50  const robot_state::RobotState& state) const
51 {
52  res.collision = false;
53  if (req.verbose)
54  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
55 }
56 
58  const robot_state::RobotState& state,
59  const AllowedCollisionMatrix& acm) const
60 {
61  res.collision = false;
62  if (req.verbose)
63  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
64 }
65 
67  const robot_state::RobotState& state1,
68  const robot_state::RobotState& state2) const
69 {
70  res.collision = false;
71  if (req.verbose)
72  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
73 }
74 
76  const robot_state::RobotState& state1,
77  const robot_state::RobotState& state2,
78  const AllowedCollisionMatrix& acm) const
79 {
80  res.collision = false;
81  if (req.verbose)
82  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
83 }
84 
86  const robot_state::RobotState& state,
87  const CollisionRobot& other_robot,
88  const robot_state::RobotState& other_state) const
89 {
90  res.collision = false;
91  if (req.verbose)
92  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
93 }
94 
96  const robot_state::RobotState& state,
97  const CollisionRobot& other_robot,
98  const robot_state::RobotState& other_state,
99  const AllowedCollisionMatrix& acm) const
100 {
101  res.collision = false;
102  if (req.verbose)
103  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
104 }
105 
107  const robot_state::RobotState& state1,
108  const robot_state::RobotState& state2,
109  const CollisionRobot& other_robot,
110  const robot_state::RobotState& other_state1,
111  const robot_state::RobotState& other_state2) const
112 {
113  res.collision = false;
114  if (req.verbose)
115  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
116 }
117 
119  const robot_state::RobotState& state1,
120  const robot_state::RobotState& state2,
121  const CollisionRobot& other_robot,
122  const robot_state::RobotState& other_state1,
123  const robot_state::RobotState& other_state2,
124  const AllowedCollisionMatrix& acm) const
125 {
126  res.collision = false;
127  if (req.verbose)
128  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
129 }
130 
132 {
133  return 0.0;
134 }
135 
137  const AllowedCollisionMatrix& acm) const
138 {
139  return 0.0;
140 }
141 
144  const moveit::core::RobotState& state) const
145 {
146  res.collision = false;
147 }
148 
150  const CollisionRobot& other_robot,
151  const robot_state::RobotState& other_state) const
152 {
153  return 0.0;
154 }
155 
157  const CollisionRobot& other_robot,
158  const robot_state::RobotState& other_state,
159  const AllowedCollisionMatrix& acm) const
160 {
161  return 0.0;
162 }
163 
166  const moveit::core::RobotState& state,
167  const collision_detection::CollisionRobot& other_robot,
168  const moveit::core::RobotState& other_state) const
169 {
170  res.collision = false;
171 }
#define ROS_INFO_NAMED(name,...)
virtual double distanceOther(const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
bool collision
True if collision was found, false otherwise.
bool verbose
Flag indicating whether information about detected collisions should be reported. ...
virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
Check for collision with a different robot (possibly a different kinematic model as well)...
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
CollisionRobotAllValid(const robot_model::RobotModelConstPtr &kmodel, double padding=0.0, double scale=1.0)
This class represents a collision model of the robot and can be used for self collision checks (to ch...
virtual double distanceSelf(const robot_state::RobotState &state) const
bool collision
Indicates if two objects were in collision.
virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const
Check for self collision. Any collision between any pair of links is checked for, NO collisions are i...
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 Wed Jul 10 2019 04:03:04