00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef COLLISION_DETECTION_COLLISION_ROBOT_INDUSTRIAL_H_
00038 #define COLLISION_DETECTION_COLLISION_ROBOT_INDUSTRIAL_H_
00039
00040 #include <moveit/collision_detection/collision_robot.h>
00041 #include <moveit/collision_detection_fcl/collision_common.h>
00042
00043 #include <industrial_collision_detection/collision_detection/collision_common.h>
00044
00045 namespace collision_detection
00046 {
00047 typedef boost::shared_ptr<fcl::CollisionObject> FCLCollisionObjectPtr;
00048 typedef boost::shared_ptr<const fcl::CollisionObject> FCLCollisionObjectConstPtr;
00049
00050 class CollisionRobotIndustrial : public CollisionRobot
00051 {
00052 friend class CollisionWorldIndustrial;
00053
00054 public:
00055
00056 CollisionRobotIndustrial(const robot_model::RobotModelConstPtr &kmodel, double padding = 0.0, double scale = 1.0);
00057
00058 CollisionRobotIndustrial(const CollisionRobotIndustrial &other);
00059
00060 virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const;
00061 virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const;
00062 virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const;
00063 virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const;
00064
00065 virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00066 const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const;
00067 virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00068 const CollisionRobot &other_robot, const robot_state::RobotState &other_state,
00069 const AllowedCollisionMatrix &acm) const;
00070 virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2,
00071 const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2) const;
00072 virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2,
00073 const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2,
00074 const AllowedCollisionMatrix &acm) const;
00075
00076 virtual double distanceSelf(const robot_state::RobotState &state) const;
00077 virtual double distanceSelf(const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const;
00078 virtual void distanceSelf(const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state) const;
00079
00080 virtual double distanceOther(const robot_state::RobotState &state,
00081 const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const;
00082 virtual double distanceOther(const robot_state::RobotState &state, const CollisionRobot &other_robot,
00083 const robot_state::RobotState &other_state, const AllowedCollisionMatrix &acm) const;
00084
00085 protected:
00086
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, const robot_state::RobotState &state,
00095 const CollisionRobot &other_robot, const robot_state::RobotState &other_state,
00096 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 void distanceSelfHelper(const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state) const;
00101
00102 std::vector<FCLGeometryConstPtr> geoms_;
00103 std::vector<FCLCollisionObjectConstPtr> fcl_objs_;
00104 };
00105
00106 typedef boost::shared_ptr<CollisionRobotIndustrial> CollisionRobotIndustrialPtr;
00107 typedef boost::shared_ptr<const CollisionRobotIndustrial> CollisionRobotIndustrialConstPtr;
00108 }
00109
00110 #endif