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 #include <moveit/collision_detection/allvalid/collision_world_allvalid.h>
00038
00039 collision_detection::CollisionWorldAllValid::CollisionWorldAllValid() : CollisionWorld()
00040 {
00041 }
00042
00043 collision_detection::CollisionWorldAllValid::CollisionWorldAllValid(const WorldPtr& world) : CollisionWorld(world)
00044 {
00045 }
00046
00047 collision_detection::CollisionWorldAllValid::CollisionWorldAllValid(const CollisionWorld &other, const WorldPtr& world) : CollisionWorld(other, world)
00048 {
00049 }
00050
00051 void collision_detection::CollisionWorldAllValid::checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
00052 {
00053 res.collision = false;
00054 if (req.verbose)
00055 logInform("Using AllValid collision detection. No collision checking is performed.");
00056 }
00057
00058 void collision_detection::CollisionWorldAllValid::checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
00059 {
00060 res.collision = false;
00061 if (req.verbose)
00062 logInform("Using AllValid collision detection. No collision checking is performed.");
00063 }
00064
00065 void collision_detection::CollisionWorldAllValid::checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const
00066 {
00067 res.collision = false;
00068 if (req.verbose)
00069 logInform("Using AllValid collision detection. No collision checking is performed.");
00070 }
00071
00072 void collision_detection::CollisionWorldAllValid::checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const
00073 {
00074 res.collision = false;
00075 if (req.verbose)
00076 logInform("Using AllValid collision detection. No collision checking is performed.");
00077 }
00078
00079 void collision_detection::CollisionWorldAllValid::checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const
00080 {
00081 res.collision = false;
00082 if (req.verbose)
00083 logInform("Using AllValid collision detection. No collision checking is performed.");
00084 }
00085
00086 void collision_detection::CollisionWorldAllValid::checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix &acm) const
00087 {
00088 res.collision = false;
00089 if (req.verbose)
00090 logInform("Using AllValid collision detection. No collision checking is performed.");
00091 }
00092
00093 double collision_detection::CollisionWorldAllValid::distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state) const
00094 {
00095 return 0.0;
00096 }
00097
00098 double collision_detection::CollisionWorldAllValid::distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
00099 {
00100 return 0.0;
00101 }
00102
00103 double collision_detection::CollisionWorldAllValid::distanceWorld(const CollisionWorld &world) const
00104 {
00105 return 0.0;
00106 }
00107
00108 double collision_detection::CollisionWorldAllValid::distanceWorld(const CollisionWorld &world, const AllowedCollisionMatrix &acm) const
00109 {
00110 return 0.0;
00111 }
00112
00113
00114 #include <moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h>
00115 const std::string collision_detection::CollisionDetectorAllocatorAllValid::NAME_("ALL_VALID");