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_robot_allvalid.h>
00038
00039 collision_detection::CollisionRobotAllValid::CollisionRobotAllValid(const robot_model::RobotModelConstPtr &kmodel, double padding, double scale) : CollisionRobot(kmodel, padding, scale)
00040 {
00041 }
00042
00043 collision_detection::CollisionRobotAllValid::CollisionRobotAllValid(const CollisionRobot &other) : CollisionRobot(other)
00044 {
00045 }
00046
00047 void collision_detection::CollisionRobotAllValid::checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const
00048 {
00049 res.collision = false;
00050 if (req.verbose)
00051 logInform("Using AllValid collision detection. No collision checking is performed.");
00052 }
00053
00054 void collision_detection::CollisionRobotAllValid::checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) 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::CollisionRobotAllValid::checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const
00062 {
00063 res.collision = false;
00064 if (req.verbose)
00065 logInform("Using AllValid collision detection. No collision checking is performed.");
00066 }
00067
00068 void collision_detection::CollisionRobotAllValid::checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const
00069 {
00070 res.collision = false;
00071 if (req.verbose)
00072 logInform("Using AllValid collision detection. No collision checking is performed.");}
00073
00074 void collision_detection::CollisionRobotAllValid::checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00075 const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
00076 {
00077 res.collision = false;
00078 if (req.verbose)
00079 logInform("Using AllValid collision detection. No collision checking is performed.");
00080 }
00081
00082 void collision_detection::CollisionRobotAllValid::checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00083 const CollisionRobot &other_robot, const robot_state::RobotState &other_state,
00084 const AllowedCollisionMatrix &acm) const
00085 {
00086 res.collision = false;
00087 if (req.verbose)
00088 logInform("Using AllValid collision detection. No collision checking is performed.");
00089 }
00090
00091 void collision_detection::CollisionRobotAllValid::checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2,
00092 const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2) const
00093 {
00094 res.collision = false;
00095 if (req.verbose)
00096 logInform("Using AllValid collision detection. No collision checking is performed.");
00097 }
00098
00099 void collision_detection::CollisionRobotAllValid::checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2,
00100 const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2,
00101 const AllowedCollisionMatrix &acm) const
00102 {
00103 res.collision = false;
00104 if (req.verbose)
00105 logInform("Using AllValid collision detection. No collision checking is performed.");
00106 }
00107
00108 double collision_detection::CollisionRobotAllValid::distanceSelf(const robot_state::RobotState &state) const
00109 {
00110 return 0.0;
00111 }
00112
00113 double collision_detection::CollisionRobotAllValid::distanceSelf(const robot_state::RobotState &state,
00114 const AllowedCollisionMatrix &acm) const
00115 {
00116 return 0.0;
00117 }
00118
00119
00120 double collision_detection::CollisionRobotAllValid::distanceOther(const robot_state::RobotState &state,
00121 const CollisionRobot &other_robot,
00122 const robot_state::RobotState &other_state) const
00123 {
00124 return 0.0;
00125 }
00126
00127 double collision_detection::CollisionRobotAllValid::distanceOther(const robot_state::RobotState &state,
00128 const CollisionRobot &other_robot,
00129 const robot_state::RobotState &other_state,
00130 const AllowedCollisionMatrix &acm) const
00131 {
00132 return 0.0;
00133 }