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_WORLD_INDUSTRIAL_H_
00038 #define COLLISION_DETECTION_COLLISION_WORLD_INDUSTRIAL_H_
00039
00040 #include <industrial_collision_detection/collision_detection/collision_robot_industrial.h>
00041 #include <fcl/broadphase/broadphase.h>
00042 #include <boost/scoped_ptr.hpp>
00043
00044 namespace collision_detection
00045 {
00046
00047 class CollisionWorldIndustrial : public CollisionWorld
00048 {
00049 public:
00050
00051 CollisionWorldIndustrial();
00052 explicit CollisionWorldIndustrial(const WorldPtr& world);
00053 CollisionWorldIndustrial(const CollisionWorldIndustrial &other, const WorldPtr& world);
00054 virtual ~CollisionWorldIndustrial();
00055
00056
00057 virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const;
00058 virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const;
00059 virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const;
00060 virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const;
00061 virtual void checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const;
00062 virtual void checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix &acm) const;
00063
00064 virtual double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state) const;
00065 virtual void distanceRobot(const DistanceRequest &req, DistanceResult &res, const collision_detection::CollisionRobot &robot, const robot_state::RobotState &state) const;
00066 virtual double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const;
00067 virtual double distanceWorld(const CollisionWorld &world) const;
00068 virtual double distanceWorld(const CollisionWorld &world, const AllowedCollisionMatrix &acm) const;
00069
00070 virtual void setWorld(const WorldPtr& world);
00071
00072 protected:
00073
00074 void checkWorldCollisionHelper(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix *acm) const;
00075 void checkRobotCollisionHelper(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const;
00076 double distanceRobotHelper(const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const;
00077 void distanceRobotHelper(const DistanceRequest &req, DistanceResult &res, const collision_detection::CollisionRobot &robot, const robot_state::RobotState &state) const;
00078 double distanceWorldHelper(const CollisionWorld &world, const AllowedCollisionMatrix *acm) const;
00079
00080 void constructFCLObject(const World::Object *obj, FCLObject &fcl_obj) const;
00081 void updateFCLObject(const std::string &id);
00082
00083
00084 boost::scoped_ptr<fcl::BroadPhaseCollisionManager> manager_;
00085 std::map<std::string, FCLObject > fcl_objs_;
00086
00087 private:
00088 void initialize();
00089 void notifyObjectChange(const ObjectConstPtr& obj, World::Action action);
00090 World::ObserverHandle observer_handle_;
00091 };
00092
00093 typedef boost::shared_ptr<CollisionWorldIndustrial> CollisionWorldIndustrialPtr;
00094 typedef boost::shared_ptr<const CollisionWorldIndustrial> CollisionWorldIndustrialConstPtr;
00095 }
00096
00097 #endif