Go to the documentation of this file.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 MOVEIT_COLLISION_DETECTION_ALLVALID_COLLISION_WORLD_ALLVALID_
00038 #define MOVEIT_COLLISION_DETECTION_ALLVALID_COLLISION_WORLD_ALLVALID_
00039
00040 #include <moveit/collision_detection/collision_world.h>
00041
00042 namespace collision_detection
00043 {
00044
00045 class CollisionRobotAllValid;
00046
00047 class CollisionWorldAllValid : public CollisionWorld
00048 {
00049 public:
00050
00051 CollisionWorldAllValid();
00052 explicit CollisionWorldAllValid(const WorldPtr& world);
00053 CollisionWorldAllValid(const CollisionWorld &other, const WorldPtr& world);
00054
00055 virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const;
00056 virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const;
00057 virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const;
00058 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;
00059
00060 virtual void checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const;
00061 virtual void checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix &acm) const;
00062
00063 virtual double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state) const;
00064 virtual double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const;
00065 virtual double distanceWorld(const CollisionWorld &world) const;
00066 virtual double distanceWorld(const CollisionWorld &world, const AllowedCollisionMatrix &acm) const;
00067 };
00068
00069 }
00070
00071 #endif