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 class CollisionRobotAllValid;
00045
00046 class CollisionWorldAllValid : public CollisionWorld
00047 {
00048 public:
00049 CollisionWorldAllValid();
00050 explicit CollisionWorldAllValid(const WorldPtr& world);
00051 CollisionWorldAllValid(const CollisionWorld& other, const WorldPtr& world);
00052
00053 virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00054 const robot_state::RobotState& state) const;
00055 virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00056 const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const;
00057 virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00058 const robot_state::RobotState& state1, const robot_state::RobotState& state2) const;
00059 virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot,
00060 const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00061 const AllowedCollisionMatrix& acm) const;
00062
00063 virtual void checkWorldCollision(const CollisionRequest& req, CollisionResult& res,
00064 const CollisionWorld& other_world) const;
00065 virtual void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, const CollisionWorld& other_world,
00066 const AllowedCollisionMatrix& acm) const;
00067
00068 virtual double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state) const;
00069 virtual double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state,
00070 const AllowedCollisionMatrix& acm) const;
00071 virtual double distanceWorld(const CollisionWorld& world) const;
00072 virtual double distanceWorld(const CollisionWorld& world, const AllowedCollisionMatrix& acm) const;
00073 };
00074 }
00075
00076 #endif