collision_robot.h
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 */
36 
37 #ifndef MOVEIT_COLLISION_DETECTION_COLLISION_ROBOT_
38 #define MOVEIT_COLLISION_DETECTION_COLLISION_ROBOT_
39 
43 #include <moveit_msgs/LinkPadding.h>
44 #include <moveit_msgs/LinkScale.h>
45 
46 namespace collision_detection
47 {
48 MOVEIT_CLASS_FORWARD(CollisionRobot);
49 
55 {
56 public:
62  CollisionRobot(const robot_model::RobotModelConstPtr& model, double padding = 0.0, double scale = 1.0); // NOLINT
63 
65  CollisionRobot(const CollisionRobot& other);
66 
67  virtual ~CollisionRobot()
68  {
69  }
70 
76  virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
77  const robot_state::RobotState& state) const = 0;
78 
85  virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
86  const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const = 0;
87 
94  virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
95  const robot_state::RobotState& state1,
96  const robot_state::RobotState& state2) const = 0;
97 
105  virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
106  const robot_state::RobotState& state1, const robot_state::RobotState& state2,
107  const AllowedCollisionMatrix& acm) const = 0;
108 
116  virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
117  const robot_state::RobotState& state, const CollisionRobot& other_robot,
118  const robot_state::RobotState& other_state) const = 0;
119 
128  virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
129  const robot_state::RobotState& state, const CollisionRobot& other_robot,
130  const robot_state::RobotState& other_state,
131  const AllowedCollisionMatrix& acm) const = 0;
132 
143  virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
144  const robot_state::RobotState& state1, const robot_state::RobotState& state2,
145  const CollisionRobot& other_robot, const robot_state::RobotState& other_state1,
146  const robot_state::RobotState& other_state2) const = 0;
147 
159  virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
160  const robot_state::RobotState& state1, const robot_state::RobotState& state2,
161  const CollisionRobot& other_robot, const robot_state::RobotState& other_state1,
162  const robot_state::RobotState& other_state2,
163  const AllowedCollisionMatrix& acm) const = 0;
164 
166  inline double distanceSelf(const robot_state::RobotState& state) const
167  {
168  DistanceRequest req;
169  DistanceResult res;
170 
171  req.enableGroup(getRobotModel());
172  distanceSelf(req, res, state);
173  return res.minimum_distance.distance;
174  }
175 
178  inline double distanceSelf(const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const
179  {
180  DistanceRequest req;
181  DistanceResult res;
182 
183  req.enableGroup(getRobotModel());
184  req.acm = &acm;
185  distanceSelf(req, res, state);
186  return res.minimum_distance.distance;
187  }
188 
193  virtual void distanceSelf(const DistanceRequest& req, DistanceResult& res,
194  const robot_state::RobotState& state) const = 0;
195 
202  inline double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot,
203  const robot_state::RobotState& other_state) const
204  {
205  DistanceRequest req;
206  DistanceResult res;
207 
208  req.enableGroup(getRobotModel());
209  distanceOther(req, res, state, other_robot, other_state);
210  return res.minimum_distance.distance;
211  }
212 
221  inline double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot,
222  const robot_state::RobotState& other_state, const AllowedCollisionMatrix& acm) const
223  {
224  DistanceRequest req;
225  DistanceResult res;
226 
227  req.enableGroup(getRobotModel());
228  req.acm = &acm;
229  distanceOther(req, res, state, other_robot, other_state);
230  return res.minimum_distance.distance;
231  }
232 
239  virtual void distanceOther(const DistanceRequest& req, DistanceResult& res, const robot_state::RobotState& state,
240  const CollisionRobot& other_robot, const robot_state::RobotState& other_state) const = 0;
241 
243  const robot_model::RobotModelConstPtr& getRobotModel() const
244  {
245  return robot_model_;
246  }
247 
252  void setLinkPadding(const std::string& link_name, double padding);
253 
255  double getLinkPadding(const std::string& link_name) const;
256 
258  void setLinkPadding(const std::map<std::string, double>& padding);
259 
261  const std::map<std::string, double>& getLinkPadding() const;
262 
264  void setLinkScale(const std::string& link_name, double scale);
265 
267  double getLinkScale(const std::string& link_name) const;
268 
270  void setLinkScale(const std::map<std::string, double>& scale);
271 
273  const std::map<std::string, double>& getLinkScale() const;
274 
276  void setPadding(double padding);
277 
279  void setScale(double scale);
280 
282  void setPadding(const std::vector<moveit_msgs::LinkPadding>& padding);
283 
285  void getPadding(std::vector<moveit_msgs::LinkPadding>& padding) const;
286 
288  void setScale(const std::vector<moveit_msgs::LinkScale>& scale);
289 
291  void getScale(std::vector<moveit_msgs::LinkScale>& scale) const;
292 
293 protected:
300  virtual void updatedPaddingOrScaling(const std::vector<std::string>& links);
301 
303  robot_model::RobotModelConstPtr robot_model_;
304 
306  std::map<std::string, double> link_padding_;
307 
309  std::map<std::string, double> link_scale_;
310 };
311 }
312 
313 #endif
void setScale(double scale)
Set the link scaling (for every link)
double distanceOther(const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
The distance to another robot instance.
std::map< std::string, double > link_scale_
The internally maintained map (from link names to scaling)
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const =0
Check for self collision. Any collision between any pair of links is checked for, NO collisions are i...
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
void setPadding(double padding)
Set the link padding (for every link)
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
double distanceOther(const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix &acm) const
The distance to another robot instance, ignoring distances between links that are allowed to always c...
const robot_model::RobotModelConstPtr & getRobotModel() const
The kinematic model corresponding to this collision model.
CollisionRobot(const robot_model::RobotModelConstPtr &model, double padding=0.0, double scale=1.0)
Constructor.
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...
Generic interface to collision detection.
void enableGroup(const robot_model::RobotModelConstPtr &kmodel)
Compute active_components_only_ based on req_.
void getScale(std::vector< moveit_msgs::LinkScale > &scale) const
Get the link scaling as a vector of messages.
robot_model::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
void getPadding(std::vector< moveit_msgs::LinkPadding > &padding) const
Get the link padding as a vector of messages.
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
void setLinkScale(const std::string &link_name, double scale)
Set the scaling for a particular link.
This class represents a collision model of the robot and can be used for self collision checks (to ch...
std::map< std::string, double > link_padding_
The internally maintained map (from link names to padding)
double distanceSelf(const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
The distance to self-collision given the robot is at state state, ignoring the distances between link...
double distance
The distance between two objects. If two objects are in collision, distance <= 0. ...
virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const =0
Check for collision with a different robot (possibly a different kinematic model as well)...
void setLinkPadding(const std::string &link_name, double padding)
Set the link padding for a particular link.
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:123
double distanceSelf(const robot_state::RobotState &state) const
The distance to self-collision given the robot is at state state.


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:04