collision_env_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, Jens Petit */
36 
39 
41 
43  double padding, double scale)
44  : CollisionEnv(robot_model, padding, scale)
45 {
46 }
47 
49  const WorldPtr& world, double padding, double scale)
50  : CollisionEnv(robot_model, world, padding, scale)
51 {
52 }
53 
55  : CollisionEnv(other, world)
56 {
57 }
58 
60  const moveit::core::RobotState& state) const
61 {
62  res.collision = false;
63  if (req.verbose)
64  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
65 }
66 
68  const moveit::core::RobotState& state,
69  const AllowedCollisionMatrix& acm) const
70 {
71  res.collision = false;
72  if (req.verbose)
73  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
74 }
75 
77  const moveit::core::RobotState& state1,
78  const moveit::core::RobotState& state2) 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 moveit::core::RobotState& state1,
87  const moveit::core::RobotState& state2,
88  const AllowedCollisionMatrix& acm) 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 
97  const moveit::core::RobotState& state) const
98 {
99  res.collision = false;
100 }
101 
103 {
104  return 0.0;
105 }
106 
108  const AllowedCollisionMatrix& acm) const
109 {
110  return 0.0;
111 }
112 
114  const moveit::core::RobotState& state) const
115 {
116  res.collision = false;
117  if (req.verbose)
118  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
119 }
120 
122  const moveit::core::RobotState& state,
123  const AllowedCollisionMatrix& acm) const
124 {
125  res.collision = false;
126  if (req.verbose)
127  ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed.");
128 }
129 
132  const moveit::core::RobotState& state) const
133 {
134  res.collision = false;
135 }
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:81
collision_detector_allocator_allvalid.h
collision_detection::CollisionDetectorAllocatorAllValid::NAME
static const std::string NAME
Definition: collision_detector_allocator_allvalid.h:113
collision_detection::CollisionEnvAllValid::checkRobotCollision
void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
Definition: collision_env_allvalid.cpp:59
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
collision_detection::CollisionRequest
Representation of a collision checking request.
Definition: include/moveit/collision_detection/collision_common.h:216
collision_env_allvalid.h
collision_detection::AllowedCollisionMatrix
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
Definition: collision_matrix.h:112
collision_detection::CollisionEnvAllValid::CollisionEnvAllValid
CollisionEnvAllValid(const moveit::core::RobotModelConstPtr &robot_model, double padding=0.0, double scale=1.0)
Definition: collision_env_allvalid.cpp:42
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
collision_detection::CollisionResult
Representation of a collision checking result.
Definition: include/moveit/collision_detection/collision_common.h:177
collision_detection::CollisionRequest::verbose
bool verbose
Flag indicating whether information about detected collisions should be reported.
Definition: include/moveit/collision_detection/collision_common.h:258
collision_detection::DistanceResult::collision
bool collision
Indicates if two objects were in collision.
Definition: include/moveit/collision_detection/collision_common.h:397
collision_detection::DistanceResult
Result of a distance request.
Definition: include/moveit/collision_detection/collision_common.h:390
collision_detection::CollisionResult::collision
bool collision
True if collision was found, false otherwise.
Definition: include/moveit/collision_detection/collision_common.h:200
collision_detection::CollisionEnvAllValid::distanceSelf
void distanceSelf(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
The distance to self-collision given the robot is at state state.
Definition: collision_env_allvalid.cpp:130
collision_detection::CollisionEnvAllValid::checkSelfCollision
void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check for robot self collision. Any collision between any pair of links is checked for,...
Definition: collision_env_allvalid.cpp:113
collision_detection::DistanceRequest
Representation of a distance-reporting request.
Definition: include/moveit/collision_detection/collision_common.h:274
collision_detection::CollisionEnv
Provides the interface to the individual collision checking libraries.
Definition: collision_env.h:83
collision_detection::CollisionEnvAllValid::distanceRobot
virtual double distanceRobot(const moveit::core::RobotState &state) const
Definition: collision_env_allvalid.cpp:102


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Dec 12 2020 03:25:44