collision_robot_fcl.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_FCL_COLLISION_ROBOT_
38 #define MOVEIT_COLLISION_DETECTION_FCL_COLLISION_ROBOT_
39 
41 
42 namespace collision_detection
43 {
45 {
46  friend class CollisionWorldFCL;
47 
48 public:
49  CollisionRobotFCL(const robot_model::RobotModelConstPtr& robot_model, double padding = 0.0, double scale = 1.0);
50 
52 
54  const robot_state::RobotState& state) const override;
56  const AllowedCollisionMatrix& acm) const override;
58  const robot_state::RobotState& state2) const override;
60  const robot_state::RobotState& state2, const AllowedCollisionMatrix& acm) const override;
61 
63  const CollisionRobot& other_robot,
64  const robot_state::RobotState& other_state) const override;
66  const CollisionRobot& other_robot, const robot_state::RobotState& other_state,
67  const AllowedCollisionMatrix& acm) const override;
69  const robot_state::RobotState& state2, const CollisionRobot& other_robot,
70  const robot_state::RobotState& other_state1,
71  const robot_state::RobotState& other_state2) const override;
73  const robot_state::RobotState& state2, const CollisionRobot& other_robot,
74  const robot_state::RobotState& other_state1, const robot_state::RobotState& other_state2,
75  const AllowedCollisionMatrix& acm) const override;
76 
77  void distanceSelf(const DistanceRequest& req, DistanceResult& res,
78  const robot_state::RobotState& state) const override;
79 
80  void distanceOther(const DistanceRequest& req, DistanceResult& res, const robot_state::RobotState& state,
81  const CollisionRobot& other_robot, const robot_state::RobotState& other_state) const override;
82 
83 protected:
84  void updatedPaddingOrScaling(const std::vector<std::string>& links) override;
85  void constructFCLObject(const robot_state::RobotState& state, FCLObject& fcl_obj) const;
86  void allocSelfCollisionBroadPhase(const robot_state::RobotState& state, FCLManager& manager) const;
87  void getAttachedBodyObjects(const robot_state::AttachedBody* ab, std::vector<FCLGeometryConstPtr>& geoms) const;
88 
90  const AllowedCollisionMatrix* acm) const;
92  const robot_state::RobotState& state, const CollisionRobot& other_robot,
93  const robot_state::RobotState& other_state, const AllowedCollisionMatrix* acm) const;
94 
95  std::vector<FCLGeometryConstPtr> geoms_;
96  std::vector<FCLCollisionObjectConstPtr> fcl_objs_;
97 };
98 }
99 
100 #endif
void allocSelfCollisionBroadPhase(const robot_state::RobotState &state, FCLManager &manager) const
Core components of MoveIt!
void getAttachedBodyObjects(const robot_state::AttachedBody *ab, std::vector< FCLGeometryConstPtr > &geoms) const
void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const override
Check for collision with a different robot (possibly a different kinematic model as well)...
std::vector< FCLGeometryConstPtr > geoms_
void updatedPaddingOrScaling(const std::vector< std::string > &links) override
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 checkSelfCollisionHelper(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
This class represents a collision model of the robot and can be used for self collision checks (to ch...
std::vector< FCLCollisionObjectConstPtr > fcl_objs_
CollisionRobotFCL(const robot_model::RobotModelConstPtr &robot_model, double padding=0.0, double scale=1.0)
void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const override
Check for self collision. Any collision between any pair of links is checked for, NO collisions are i...
void checkOtherCollisionHelper(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix *acm) const
void distanceSelf(const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state) const override
The distance to self-collision given the robot is at state state.
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:123
Object defining bodies that can be attached to robot links. This is useful when handling objects pick...
Definition: attached_body.h:56
void distanceOther(const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const override
The distance to self-collision given the robot is at state state.
void constructFCLObject(const robot_state::RobotState &state, FCLObject &fcl_obj) const


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Jun 13 2019 19:54:59