moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 #include <rclcpp/logger.hpp>
40 #include <rclcpp/logging.hpp>
41 
42 // Logger
43 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_collision_detection.collision_world_allvalid");
44 
46 
47 collision_detection::CollisionEnvAllValid::CollisionEnvAllValid(const moveit::core::RobotModelConstPtr& robot_model,
48  double padding, double scale)
49  : CollisionEnv(robot_model, padding, scale)
50 {
51 }
52 
53 collision_detection::CollisionEnvAllValid::CollisionEnvAllValid(const moveit::core::RobotModelConstPtr& robot_model,
54  const WorldPtr& world, double padding, double scale)
55  : CollisionEnv(robot_model, world, padding, scale)
56 {
57 }
58 
60  : CollisionEnv(other, world)
61 {
62 }
63 
65  const moveit::core::RobotState& /*state*/) const
66 {
67  res.collision = false;
68  if (req.verbose)
69  RCLCPP_INFO(LOGGER, "Using AllValid collision detection. No collision checking is performed.");
70 }
71 
73  const moveit::core::RobotState& /*state*/,
74  const AllowedCollisionMatrix& /*acm*/) const
75 {
76  res.collision = false;
77  if (req.verbose)
78  RCLCPP_INFO(LOGGER, "Using AllValid collision detection. No collision checking is performed.");
79 }
80 
82  const moveit::core::RobotState& /*state1*/,
83  const moveit::core::RobotState& /*state2*/) const
84 {
85  res.collision = false;
86  if (req.verbose)
87  RCLCPP_INFO(LOGGER, "Using AllValid collision detection. No collision checking is performed.");
88 }
89 
91  const moveit::core::RobotState& /*state1*/,
92  const moveit::core::RobotState& /*state2*/,
93  const AllowedCollisionMatrix& /*acm*/) const
94 {
95  res.collision = false;
96  if (req.verbose)
97  RCLCPP_INFO(LOGGER, "Using AllValid collision detection. No collision checking is performed.");
98 }
99 
102  const moveit::core::RobotState& /*state*/) const
103 {
104  res.collision = false;
105 }
106 
108 {
109  return 0.0;
110 }
111 
113  const AllowedCollisionMatrix& /*acm*/) const
114 {
115  return 0.0;
116 }
117 
119  const moveit::core::RobotState& /*state*/) const
120 {
121  res.collision = false;
122  if (req.verbose)
123  RCLCPP_INFO(LOGGER, "Using AllValid collision detection. No collision checking is performed.");
124 }
125 
127  const moveit::core::RobotState& /*state*/,
128  const AllowedCollisionMatrix& /*acm*/) const
129 {
130  res.collision = false;
131  if (req.verbose)
132  RCLCPP_INFO(LOGGER, "Using AllValid collision detection. No collision checking is performed.");
133 }
134 
137  const moveit::core::RobotState& /*state*/) const
138 {
139  res.collision = false;
140 }
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
CollisionEnvAllValid(const moveit::core::RobotModelConstPtr &robot_model, double padding=0.0, double scale=1.0)
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,...
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...
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.
virtual double distanceRobot(const moveit::core::RobotState &state) const
Provides the interface to the individual collision checking libraries.
Definition: collision_env.h:52
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
Representation of a collision checking request.
bool verbose
Flag indicating whether information about detected collisions should be reported.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
Representation of a distance-reporting request.
Result of a distance request.
bool collision
Indicates if two objects were in collision.