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_COLLISION_ROBOT_
00038 #define MOVEIT_COLLISION_DETECTION_COLLISION_ROBOT_
00039
00040 #include <moveit/collision_detection/collision_matrix.h>
00041 #include <moveit/macros/class_forward.h>
00042 #include <moveit/robot_state/robot_state.h>
00043 #include <moveit_msgs/LinkPadding.h>
00044 #include <moveit_msgs/LinkScale.h>
00045
00046 namespace collision_detection
00047 {
00048 MOVEIT_CLASS_FORWARD(CollisionRobot);
00049
00054 class CollisionRobot
00055 {
00056 public:
00062 CollisionRobot(const robot_model::RobotModelConstPtr& model, double padding = 0.0, double scale = 1.0);
00063
00065 CollisionRobot(const CollisionRobot& other);
00066
00067 virtual ~CollisionRobot()
00068 {
00069 }
00070
00076 virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00077 const robot_state::RobotState& state) const = 0;
00078
00085 virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00086 const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const = 0;
00087
00094 virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00095 const robot_state::RobotState& state1,
00096 const robot_state::RobotState& state2) const = 0;
00097
00105 virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
00106 const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00107 const AllowedCollisionMatrix& acm) const = 0;
00108
00116 virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00117 const robot_state::RobotState& state, const CollisionRobot& other_robot,
00118 const robot_state::RobotState& other_state) const = 0;
00119
00128 virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00129 const robot_state::RobotState& state, const CollisionRobot& other_robot,
00130 const robot_state::RobotState& other_state,
00131 const AllowedCollisionMatrix& acm) const = 0;
00132
00143 virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00144 const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00145 const CollisionRobot& other_robot, const robot_state::RobotState& other_state1,
00146 const robot_state::RobotState& other_state2) const = 0;
00147
00159 virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res,
00160 const robot_state::RobotState& state1, const robot_state::RobotState& state2,
00161 const CollisionRobot& other_robot, const robot_state::RobotState& other_state1,
00162 const robot_state::RobotState& other_state2,
00163 const AllowedCollisionMatrix& acm) const = 0;
00164
00166 virtual double distanceSelf(const robot_state::RobotState& state) const = 0;
00167
00170 virtual double distanceSelf(const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const = 0;
00171
00176 virtual double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot,
00177 const robot_state::RobotState& other_state) const = 0;
00178
00185 virtual double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot,
00186 const robot_state::RobotState& other_state, const AllowedCollisionMatrix& acm) const = 0;
00187
00189 const robot_model::RobotModelConstPtr& getRobotModel() const
00190 {
00191 return robot_model_;
00192 }
00193
00198 void setLinkPadding(const std::string& link_name, double padding);
00199
00201 double getLinkPadding(const std::string& link_name) const;
00202
00204 void setLinkPadding(const std::map<std::string, double>& padding);
00205
00207 const std::map<std::string, double>& getLinkPadding() const;
00208
00210 void setLinkScale(const std::string& link_name, double scale);
00211
00213 double getLinkScale(const std::string& link_name) const;
00214
00216 void setLinkScale(const std::map<std::string, double>& scale);
00217
00219 const std::map<std::string, double>& getLinkScale() const;
00220
00222 void setPadding(double padding);
00223
00225 void setScale(double scale);
00226
00228 void setPadding(const std::vector<moveit_msgs::LinkPadding>& padding);
00229
00231 void getPadding(std::vector<moveit_msgs::LinkPadding>& padding) const;
00232
00234 void setScale(const std::vector<moveit_msgs::LinkScale>& scale);
00235
00237 void getScale(std::vector<moveit_msgs::LinkScale>& scale) const;
00238
00239 protected:
00246 virtual void updatedPaddingOrScaling(const std::vector<std::string>& links);
00247
00249 robot_model::RobotModelConstPtr robot_model_;
00250
00252 std::map<std::string, double> link_padding_;
00253
00255 std::map<std::string, double> link_scale_;
00256 };
00257 }
00258
00259 #endif