collision_robot_fcl.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #ifndef MOVEIT_COLLISION_DETECTION_FCL_COLLISION_ROBOT_
00038 #define MOVEIT_COLLISION_DETECTION_FCL_COLLISION_ROBOT_
00039 
00040 #include <moveit/collision_detection_fcl/collision_common.h>
00041 
00042 namespace collision_detection
00043 {
00044 class CollisionRobotFCL : public CollisionRobot
00045 {
00046   friend class CollisionWorldFCL;
00047 
00048 public:
00049   CollisionRobotFCL(const robot_model::RobotModelConstPtr& kmodel, double padding = 0.0, double scale = 1.0);
00050 
00051   CollisionRobotFCL(const CollisionRobotFCL& other);
00052 
00053   virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00054                                   const robot_state::RobotState& state) const;
00055   virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00056                                   const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const;
00057   virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00058                                   const robot_state::RobotState& state1, const robot_state::RobotState& state2) const;
00059   virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00060                                   const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00061                                   const AllowedCollisionMatrix& acm) const;
00062 
00063   virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00064                                    const robot_state::RobotState& state, const CollisionRobot& other_robot,
00065                                    const robot_state::RobotState& other_state) const;
00066   virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00067                                    const robot_state::RobotState& state, const CollisionRobot& other_robot,
00068                                    const robot_state::RobotState& other_state, const AllowedCollisionMatrix& acm) const;
00069   virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00070                                    const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00071                                    const CollisionRobot& other_robot, const robot_state::RobotState& other_state1,
00072                                    const robot_state::RobotState& other_state2) const;
00073   virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00074                                    const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00075                                    const CollisionRobot& other_robot, const robot_state::RobotState& other_state1,
00076                                    const robot_state::RobotState& other_state2,
00077                                    const AllowedCollisionMatrix& acm) const;
00078 
00079   virtual double distanceSelf(const robot_state::RobotState& state) const;
00080   virtual double distanceSelf(const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const;
00081   virtual double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot,
00082                                const robot_state::RobotState& other_state) const;
00083   virtual double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot,
00084                                const robot_state::RobotState& other_state, const AllowedCollisionMatrix& acm) const;
00085 
00086 protected:
00087   virtual void updatedPaddingOrScaling(const std::vector<std::string>& links);
00088   void constructFCLObject(const robot_state::RobotState& state, FCLObject& fcl_obj) const;
00089   void allocSelfCollisionBroadPhase(const robot_state::RobotState& state, FCLManager& manager) const;
00090   void getAttachedBodyObjects(const robot_state::AttachedBody* ab, std::vector<FCLGeometryConstPtr>& geoms) const;
00091 
00092   void checkSelfCollisionHelper(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state,
00093                                 const AllowedCollisionMatrix* acm) const;
00094   void checkOtherCollisionHelper(const CollisionRequest& req, CollisionResult& res,
00095                                  const robot_state::RobotState& state, const CollisionRobot& other_robot,
00096                                  const robot_state::RobotState& other_state, const AllowedCollisionMatrix* acm) const;
00097   double distanceSelfHelper(const robot_state::RobotState& state, const AllowedCollisionMatrix* acm) const;
00098   double distanceOtherHelper(const robot_state::RobotState& state, const CollisionRobot& other_robot,
00099                              const robot_state::RobotState& other_state, const AllowedCollisionMatrix* acm) const;
00100 
00101   std::vector<FCLGeometryConstPtr> geoms_;
00102   std::vector<FCLCollisionObjectConstPtr> fcl_objs_;
00103 };
00104 }
00105 
00106 #endif


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jun 19 2019 19:23:49