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 <vector>
00043
00052 namespace constraint_samplers
00053 {
00054 MOVEIT_CLASS_FORWARD(ConstraintSampler);
00055
00060 class ConstraintSampler
00061 {
00062 public:
00065 static const unsigned int DEFAULT_MAX_SAMPLING_ATTEMPTS = 2;
00066
00076 ConstraintSampler(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name);
00077
00078 virtual ~ConstraintSampler()
00079 {
00080 }
00081
00090 virtual bool configure(const moveit_msgs::Constraints& constr) = 0;
00091
00097 const std::string& getGroupName() const
00098 {
00099 return getJointModelGroup()->getName();
00100 }
00101
00108 const robot_model::JointModelGroup* getJointModelGroup() const
00109 {
00110 return jmg_;
00111 }
00112
00119 const planning_scene::PlanningSceneConstPtr& getPlanningScene() const
00120 {
00121 return scene_;
00122 }
00123
00135 const std::vector<std::string>& getFrameDependency() const
00136 {
00137 return frame_depends_;
00138 }
00139
00144 const robot_state::GroupStateValidityCallbackFn& getGroupStateValidityCallback() const
00145 {
00146 return group_state_validity_callback_;
00147 }
00148
00155 void setGroupStateValidityCallback(const robot_state::GroupStateValidityCallbackFn& callback)
00156 {
00157 group_state_validity_callback_ = callback;
00158 }
00159
00170 bool sample(robot_state::RobotState& state)
00171 {
00172 return sample(state, state, DEFAULT_MAX_SAMPLING_ATTEMPTS);
00173 }
00174
00186 bool sample(robot_state::RobotState& state, unsigned int max_attempts)
00187 {
00188 return sample(state, state, max_attempts);
00189 }
00190
00201 bool sample(robot_state::RobotState& state, const robot_state::RobotState& reference_state)
00202 {
00203 return sample(state, reference_state, DEFAULT_MAX_SAMPLING_ATTEMPTS);
00204 }
00205
00216 bool project(robot_state::RobotState& state)
00217 {
00218 return project(state, DEFAULT_MAX_SAMPLING_ATTEMPTS);
00219 }
00220
00232 virtual bool sample(robot_state::RobotState& state, const robot_state::RobotState& reference_state,
00233 unsigned int max_attempts) = 0;
00234
00246 virtual bool project(robot_state::RobotState& state, unsigned int max_attempts) = 0;
00247
00255 bool isValid() const
00256 {
00257 return is_valid_;
00258 }
00259
00261 bool getVerbose() const
00262 {
00263 return verbose_;
00264 }
00265
00267 virtual void setVerbose(bool verbose)
00268 {
00269 verbose_ = verbose;
00270 }
00271
00277 virtual const std::string& getName() const = 0;
00278
00279 protected:
00284 virtual void clear();
00285
00286 bool is_valid_;
00288 planning_scene::PlanningSceneConstPtr scene_;
00289 const robot_model::JointModelGroup* jmg_;
00291 std::vector<std::string> frame_depends_;
00292 robot_state::GroupStateValidityCallbackFn group_state_validity_callback_;
00294 bool verbose_;
00295 };
00296 }
00297
00298 #endif