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_ROBOT_ALLVALID_
00038 #define MOVEIT_COLLISION_DETECTION_ALLVALID_COLLISION_ROBOT_ALLVALID_
00039
00040 #include <moveit/collision_detection/collision_robot.h>
00041
00042 namespace collision_detection
00043 {
00044
00045 class CollisionRobotAllValid : public CollisionRobot
00046 {
00047 public:
00048
00049 CollisionRobotAllValid(const robot_model::RobotModelConstPtr &kmodel, double padding = 0.0, double scale = 1.0);
00050 CollisionRobotAllValid(const CollisionRobot &other);
00051
00052 virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const;
00053 virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const;
00054 virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const;
00055 virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const;
00056
00057 virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00058 const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const;
00059 virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00060 const CollisionRobot &other_robot, const robot_state::RobotState &other_state,
00061 const AllowedCollisionMatrix &acm) const;
00062 virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2,
00063 const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2) const;
00064 virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2,
00065 const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2,
00066 const AllowedCollisionMatrix &acm) const;
00067
00068 virtual double distanceSelf(const robot_state::RobotState &state) const;
00069 virtual double distanceSelf(const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const;
00070
00071 virtual double distanceOther(const robot_state::RobotState &state,
00072 const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const;
00073 virtual double distanceOther(const robot_state::RobotState &state, const CollisionRobot &other_robot,
00074 const robot_state::RobotState &other_state, const AllowedCollisionMatrix &acm) const;
00075
00076 };
00077
00078 }
00079
00080 #endif