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 class CollisionRobotAllValid : public CollisionRobot
00045 {
00046 public:
00047 CollisionRobotAllValid(const robot_model::RobotModelConstPtr& kmodel, double padding = 0.0, double scale = 1.0);
00048 CollisionRobotAllValid(const CollisionRobot& other);
00049
00050 virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00051 const robot_state::RobotState& state) const;
00052 virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00053 const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const;
00054 virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00055 const robot_state::RobotState& state1, const robot_state::RobotState& state2) const;
00056 virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00057 const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00058 const AllowedCollisionMatrix& acm) const;
00059
00060 virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00061 const robot_state::RobotState& state, const CollisionRobot& other_robot,
00062 const robot_state::RobotState& other_state) const;
00063 virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00064 const robot_state::RobotState& state, const CollisionRobot& other_robot,
00065 const robot_state::RobotState& other_state, const AllowedCollisionMatrix& acm) const;
00066 virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00067 const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00068 const CollisionRobot& other_robot, const robot_state::RobotState& other_state1,
00069 const robot_state::RobotState& other_state2) const;
00070 virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00071 const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00072 const CollisionRobot& other_robot, const robot_state::RobotState& other_state1,
00073 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
00079 virtual double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot,
00080 const robot_state::RobotState& other_state) const;
00081 virtual double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot,
00082 const robot_state::RobotState& other_state, const AllowedCollisionMatrix& acm) const;
00083 };
00084 }
00085
00086 #endif