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