moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_env.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 the copyright holder 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, Jens Petit */
36 
38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
40 #include <limits>
41 
42 // Logger
43 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_collision_detection.collision_robot");
44 
45 static inline bool validateScale(const double scale)
46 {
47  if (scale < std::numeric_limits<double>::epsilon())
48  {
49  RCLCPP_ERROR(LOGGER, "Scale must be positive");
50  return false;
51  }
52  if (scale > std::numeric_limits<double>::max())
53  {
54  RCLCPP_ERROR(LOGGER, "Scale must be finite");
55  return false;
56  }
57  return true;
58 }
59 
60 static inline bool validatePadding(const double padding)
61 {
62  if (padding < 0.0)
63  {
64  RCLCPP_ERROR(LOGGER, "Padding cannot be negative");
65  return false;
66  }
67  if (padding > std::numeric_limits<double>::max())
68  {
69  RCLCPP_ERROR(LOGGER, "Padding must be finite");
70  return false;
71  }
72  return true;
73 }
74 
75 namespace collision_detection
76 {
77 CollisionEnv::CollisionEnv(const moveit::core::RobotModelConstPtr& model, double padding, double scale)
78  : robot_model_(model), world_(std::make_shared<World>()), world_const_(world_)
79 {
80  if (!validateScale(scale))
81  scale = 1.0;
82  if (!validatePadding(padding))
83  padding = 0.0;
84 
85  const std::vector<const moveit::core::LinkModel*>& links = robot_model_->getLinkModelsWithCollisionGeometry();
86  for (const auto link : links)
87  {
88  link_padding_[link->getName()] = padding;
89  link_scale_[link->getName()] = scale;
90  }
91 }
92 
93 CollisionEnv::CollisionEnv(const moveit::core::RobotModelConstPtr& model, const WorldPtr& world, double padding,
94  double scale)
95  : robot_model_(model), world_(world), world_const_(world_)
96 {
97  if (!validateScale(scale))
98  scale = 1.0;
99  if (!validatePadding(padding))
100  padding = 0.0;
101 
102  const std::vector<const moveit::core::LinkModel*>& links = robot_model_->getLinkModelsWithCollisionGeometry();
103  for (const auto link : links)
104  {
105  link_padding_[link->getName()] = padding;
106  link_scale_[link->getName()] = scale;
107  }
108 }
109 
110 CollisionEnv::CollisionEnv(const CollisionEnv& other, const WorldPtr& world)
111  : robot_model_(other.robot_model_), world_(world), world_const_(world)
112 {
114  link_scale_ = other.link_scale_;
115 }
116 void CollisionEnv::setPadding(const double padding)
117 {
118  if (!validatePadding(padding))
119  return;
120  std::vector<std::string> u;
121  const std::vector<const moveit::core::LinkModel*>& links = robot_model_->getLinkModelsWithCollisionGeometry();
122  for (const auto link : links)
123  {
124  if (getLinkPadding(link->getName()) != padding)
125  u.push_back(link->getName());
126  link_padding_[link->getName()] = padding;
127  }
128  if (!u.empty())
130 }
131 
132 void CollisionEnv::setScale(const double scale)
133 {
134  if (!validateScale(scale))
135  return;
136  std::vector<std::string> u;
137  const std::vector<const moveit::core::LinkModel*>& links = robot_model_->getLinkModelsWithCollisionGeometry();
138  for (const auto link : links)
139  {
140  if (getLinkScale(link->getName()) != scale)
141  u.push_back(link->getName());
142  link_scale_[link->getName()] = scale;
143  }
144  if (!u.empty())
146 }
147 
148 void CollisionEnv::setLinkPadding(const std::string& link_name, const double padding)
149 {
150  validatePadding(padding);
151  const bool update = getLinkPadding(link_name) != padding;
152  link_padding_[link_name] = padding;
153  if (update)
154  {
155  std::vector<std::string> u(1, link_name);
157  }
158 }
159 
160 double CollisionEnv::getLinkPadding(const std::string& link_name) const
161 {
162  auto it = link_padding_.find(link_name);
163  if (it != link_padding_.end())
164  return it->second;
165  else
166  return 0.0;
167 }
168 
169 void CollisionEnv::setLinkPadding(const std::map<std::string, double>& padding)
170 {
171  std::vector<std::string> u;
172  for (const auto& link_pad_pair : padding)
173  {
174  validatePadding(link_pad_pair.second);
175  const bool update = getLinkPadding(link_pad_pair.first) != link_pad_pair.second;
176  link_padding_[link_pad_pair.first] = link_pad_pair.second;
177  if (update)
178  u.push_back(link_pad_pair.first);
179  }
180  if (!u.empty())
182 }
183 
184 const std::map<std::string, double>& CollisionEnv::getLinkPadding() const
185 {
186  return link_padding_;
187 }
188 
189 void CollisionEnv::setLinkScale(const std::string& link_name, const double scale)
190 {
191  validateScale(scale);
192  const bool update = getLinkScale(link_name) != scale;
193  link_scale_[link_name] = scale;
194  if (update)
195  {
196  std::vector<std::string> u(1, link_name);
198  }
199 }
200 
201 double CollisionEnv::getLinkScale(const std::string& link_name) const
202 {
203  const auto it = link_scale_.find(link_name);
204  if (it != link_scale_.end())
205  return it->second;
206  else
207  return 1.0;
208 }
209 
210 void CollisionEnv::setLinkScale(const std::map<std::string, double>& scale)
211 {
212  std::vector<std::string> u;
213  for (const auto& link_scale_pair : scale)
214  {
215  const bool update = getLinkScale(link_scale_pair.first) != link_scale_pair.second;
216  link_scale_[link_scale_pair.first] = link_scale_pair.second;
217  if (update)
218  u.push_back(link_scale_pair.first);
219  }
220  if (!u.empty())
222 }
223 
224 const std::map<std::string, double>& CollisionEnv::getLinkScale() const
225 {
226  return link_scale_;
227 }
228 
229 void CollisionEnv::setPadding(const std::vector<moveit_msgs::msg::LinkPadding>& padding)
230 {
231  std::vector<std::string> u;
232  for (const auto& p : padding)
233  {
234  validatePadding(p.padding);
235  const bool update = getLinkPadding(p.link_name) != p.padding;
236  link_padding_[p.link_name] = p.padding;
237  if (update)
238  u.push_back(p.link_name);
239  }
240  if (!u.empty())
242 }
243 
244 void CollisionEnv::setScale(const std::vector<moveit_msgs::msg::LinkScale>& scale)
245 {
246  std::vector<std::string> u;
247  for (const auto& s : scale)
248  {
249  validateScale(s.scale);
250  const bool update = getLinkScale(s.link_name) != s.scale;
251  link_scale_[s.link_name] = s.scale;
252  if (update)
253  u.push_back(s.link_name);
254  }
255  if (!u.empty())
257 }
258 
259 void CollisionEnv::getPadding(std::vector<moveit_msgs::msg::LinkPadding>& padding) const
260 {
261  padding.clear();
262  for (const auto& lp : link_padding_)
263  {
264  moveit_msgs::msg::LinkPadding lp_msg;
265  lp_msg.link_name = lp.first;
266  lp_msg.padding = lp.second;
267  padding.push_back(lp_msg);
268  }
269 }
270 
271 void CollisionEnv::getScale(std::vector<moveit_msgs::msg::LinkScale>& scale) const
272 {
273  scale.clear();
274  for (const auto& ls : link_scale_)
275  {
276  moveit_msgs::msg::LinkScale ls_msg;
277  ls_msg.link_name = ls.first;
278  ls_msg.scale = ls.second;
279  scale.push_back(ls_msg);
280  }
281 }
282 
283 void CollisionEnv::updatedPaddingOrScaling(const std::vector<std::string>& /*links*/)
284 {
285 }
286 
287 void CollisionEnv::setWorld(const WorldPtr& world)
288 {
289  world_ = world;
290  if (!world_)
291  world_ = std::make_shared<World>();
292 
293  world_const_ = world;
294 }
295 
297  const moveit::core::RobotState& state) const
298 {
299  checkSelfCollision(req, res, state);
300  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
301  checkRobotCollision(req, res, state);
302 }
303 
305  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm) const
306 {
307  checkSelfCollision(req, res, state, acm);
308  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
309  checkRobotCollision(req, res, state, acm);
310 }
311 } // end of namespace collision_detection
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
Provides the interface to the individual collision checking libraries.
Definition: collision_env.h:52
virtual void setWorld(const WorldPtr &world)
void getPadding(std::vector< moveit_msgs::msg::LinkPadding > &padding) const
Get the link padding as a vector of messages.
void setLinkScale(const std::string &link_name, double scale)
Set the scaling for a particular link.
void setLinkPadding(const std::string &link_name, double padding)
Set the link padding for a particular link.
moveit::core::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const =0
Check for robot self collision. Any collision between any pair of links is checked for,...
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
void setScale(double scale)
Set the link scaling (for every link)
void setPadding(double padding)
Set the link padding (for every link)
virtual void checkCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const
Check whether the robot model is in collision with itself or the world at a particular state....
void getScale(std::vector< moveit_msgs::msg::LinkScale > &scale) const
Get the link scaling as a vector of messages.
std::map< std::string, double > link_padding_
The internally maintained map (from link names to padding)
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const =0
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
virtual void updatedPaddingOrScaling(const std::vector< std::string > &links)
When the scale or padding is changed for a set of links by any of the functions in this class,...
std::map< std::string, double > link_scale_
The internally maintained map (from link names to scaling)
Maintain a representation of the environment.
Definition: world.h:59
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
p
Definition: pick.py:62
Representation of a collision checking request.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
std::size_t max_contacts
Overall maximum number of contacts to compute.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.