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 the 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 
00045   class CollisionRobotFCL : public CollisionRobot
00046   {
00047     friend class CollisionWorldFCL;
00048 
00049   public:
00050 
00051     CollisionRobotFCL(const robot_model::RobotModelConstPtr &kmodel, double padding = 0.0, double scale = 1.0);
00052 
00053     CollisionRobotFCL(const CollisionRobotFCL &other);
00054 
00055     virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const;
00056     virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const;
00057     virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const;
00058     virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const;
00059 
00060     virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00061                                      const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const;
00062     virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00063                                      const CollisionRobot &other_robot, const robot_state::RobotState &other_state,
00064                                      const AllowedCollisionMatrix &acm) const;
00065     virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2,
00066                                      const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2) const;
00067     virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2,
00068                                      const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2,
00069                                      const AllowedCollisionMatrix &acm) const;
00070 
00071     virtual double distanceSelf(const robot_state::RobotState &state) const;
00072     virtual double distanceSelf(const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const;
00073     virtual double distanceOther(const robot_state::RobotState &state,
00074                                  const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const;
00075     virtual double distanceOther(const robot_state::RobotState &state, const CollisionRobot &other_robot,
00076                                  const robot_state::RobotState &other_state, const AllowedCollisionMatrix &acm) const;
00077 
00078   protected:
00079 
00080     virtual void updatedPaddingOrScaling(const std::vector<std::string> &links);
00081     void constructFCLObject(const robot_state::RobotState &state, FCLObject &fcl_obj) const;
00082     void allocSelfCollisionBroadPhase(const robot_state::RobotState &state, FCLManager &manager) const;
00083     void getAttachedBodyObjects(const robot_state::AttachedBody *ab, std::vector<FCLGeometryConstPtr> &geoms) const;
00084 
00085     void checkSelfCollisionHelper(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00086                                   const AllowedCollisionMatrix *acm) const;
00087     void checkOtherCollisionHelper(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00088                                    const CollisionRobot &other_robot, const robot_state::RobotState &other_state,
00089                                    const AllowedCollisionMatrix *acm) const;
00090     double distanceSelfHelper(const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const;
00091     double distanceOtherHelper(const robot_state::RobotState &state, const CollisionRobot &other_robot,
00092                                const robot_state::RobotState &other_state, const AllowedCollisionMatrix *acm) const;
00093 
00094     std::vector<const robot_model::LinkModel*> links_;
00095     std::vector<FCLGeometryConstPtr>               geoms_;
00096     std::map<std::string, std::size_t>             index_map_;
00097   };
00098 
00099 }
00100 
00101 #endif


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:46