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