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 #ifndef MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_
00038 #define MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_
00039
00040 #include <moveit/planning_scene/planning_scene.h>
00041 #include <moveit/kinematic_constraints/kinematic_constraint.h>
00042 #include <boost/shared_ptr.hpp>
00043 #include <vector>
00044
00053 namespace constraint_samplers
00054 {
00059 class ConstraintSampler
00060 {
00061 public:
00062
00063 static const unsigned int DEFAULT_MAX_SAMPLING_ATTEMPTS = 2;
00071 ConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name);
00072
00073 virtual ~ConstraintSampler()
00074 {
00075 }
00076
00084 virtual bool configure(const moveit_msgs::Constraints &constr) = 0;
00085
00091 const std::string& getGroupName() const
00092 {
00093 return getJointModelGroup()->getName();
00094 }
00095
00102 const robot_model::JointModelGroup* getJointModelGroup() const
00103 {
00104 return jmg_;
00105 }
00106
00113 const planning_scene::PlanningSceneConstPtr& getPlanningScene() const
00114 {
00115 return scene_;
00116 }
00117
00129 const std::vector<std::string>& getFrameDependency() const
00130 {
00131 return frame_depends_;
00132 }
00133
00137 const robot_state::StateValidityCallbackFn& getStateValidityCallback() const
00138 {
00139 return state_validity_callback_;
00140 }
00141
00147 void setStateValidityCallback(const robot_state::StateValidityCallbackFn &callback)
00148 {
00149 state_validity_callback_ = callback;
00150 }
00151
00162 bool sample(robot_state::JointStateGroup *jsg,
00163 const robot_state::RobotState &reference_state)
00164 {
00165 return sample(jsg, reference_state, DEFAULT_MAX_SAMPLING_ATTEMPTS);
00166 }
00167
00178 bool project(robot_state::JointStateGroup *jsg,
00179 const robot_state::RobotState &reference_state)
00180 {
00181 return project(jsg, reference_state, DEFAULT_MAX_SAMPLING_ATTEMPTS);
00182 }
00183
00194 virtual bool sample(robot_state::JointStateGroup *jsg,
00195 const robot_state::RobotState &reference_state,
00196 unsigned int max_attempts) = 0;
00197
00208 virtual bool project(robot_state::JointStateGroup *jsg,
00209 const robot_state::RobotState &reference_state,
00210 unsigned int max_attempts) = 0;
00211
00217 bool isValid() const
00218 {
00219 return is_valid_;
00220 }
00221
00223 bool getVerbose() const
00224 {
00225 return verbose_;
00226 }
00227
00229 void setVerbose(bool flag)
00230 {
00231 verbose_ = flag;
00232 }
00233
00234 protected:
00235
00240 virtual void clear();
00241
00242 bool is_valid_;
00244 planning_scene::PlanningSceneConstPtr scene_;
00245 const robot_model::JointModelGroup *jmg_;
00246 std::vector<std::string> frame_depends_;
00247 robot_state::StateValidityCallbackFn state_validity_callback_;
00248 bool verbose_;
00249 };
00250
00251 typedef boost::shared_ptr<ConstraintSampler> ConstraintSamplerPtr;
00252 typedef boost::shared_ptr<const ConstraintSampler> ConstraintSamplerConstPtr;
00253 }
00254
00255
00256 #endif