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 #include <moveit/utils/logger.hpp>
42 
43 namespace collision_detection
44 {
45 namespace
46 {
47 rclcpp::Logger getLogger()
48 {
49  return moveit::getLogger("moveit.core.collision_detection.env_allvalid");
50 }
51 } // namespace
52 
53 const std::string CollisionDetectorAllocatorAllValid::NAME("ALL_VALID");
54 
55 CollisionEnvAllValid::CollisionEnvAllValid(const moveit::core::RobotModelConstPtr& robot_model, double padding,
56  double scale)
57  : CollisionEnv(robot_model, padding, scale)
58 {
59 }
60 
61 CollisionEnvAllValid::CollisionEnvAllValid(const moveit::core::RobotModelConstPtr& robot_model, const WorldPtr& world,
62  double padding, double scale)
63  : CollisionEnv(robot_model, world, padding, scale)
64 {
65 }
66 
67 CollisionEnvAllValid::CollisionEnvAllValid(const CollisionEnv& other, const WorldPtr& world)
68  : CollisionEnv(other, world)
69 {
70 }
71 
73  const moveit::core::RobotState& /*state*/) const
74 {
75  res.collision = false;
76  if (req.verbose)
77  RCLCPP_INFO(getLogger(), "Using AllValid collision detection. No collision checking is performed.");
78 }
79 
81  const moveit::core::RobotState& /*state*/,
82  const AllowedCollisionMatrix& /*acm*/) const
83 {
84  res.collision = false;
85  if (req.verbose)
86  RCLCPP_INFO(getLogger(), "Using AllValid collision detection. No collision checking is performed.");
87 }
88 
90  const moveit::core::RobotState& /*state1*/,
91  const moveit::core::RobotState& /*state2*/) const
92 {
93  res.collision = false;
94  if (req.verbose)
95  RCLCPP_INFO(getLogger(), "Using AllValid collision detection. No collision checking is performed.");
96 }
97 
99  const moveit::core::RobotState& /*state1*/,
100  const moveit::core::RobotState& /*state2*/,
101  const AllowedCollisionMatrix& /*acm*/) const
102 {
103  res.collision = false;
104  if (req.verbose)
105  RCLCPP_INFO(getLogger(), "Using AllValid collision detection. No collision checking is performed.");
106 }
107 
109  const moveit::core::RobotState& /*state*/) const
110 {
111  res.collision = false;
112 }
113 
115 {
116  return 0.0;
117 }
118 
120  const AllowedCollisionMatrix& /*acm*/) const
121 {
122  return 0.0;
123 }
124 
126  const moveit::core::RobotState& /*state*/) const
127 {
128  res.collision = false;
129  if (req.verbose)
130  RCLCPP_INFO(getLogger(), "Using AllValid collision detection. No collision checking is performed.");
131 }
132 
134  const moveit::core::RobotState& /*state*/,
135  const AllowedCollisionMatrix& /*acm*/) const
136 {
137  res.collision = false;
138  if (req.verbose)
139  RCLCPP_INFO(getLogger(), "Using AllValid collision detection. No collision checking is performed.");
140 }
141 
143  const moveit::core::RobotState& /*state*/) const
144 {
145  res.collision = false;
146 }
147 
148 } // namespace collision_detection
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
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
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.