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/ompl_interface/detail/constrained_goal_sampler.h>
00038 #include <moveit/ompl_interface/model_based_planning_context.h>
00039 #include <moveit/ompl_interface/detail/state_validity_checker.h>
00040 #include <moveit/profiler/profiler.h>
00041
00042 ompl_interface::ConstrainedGoalSampler::ConstrainedGoalSampler(const ModelBasedPlanningContext *pc,
00043 const kinematic_constraints::KinematicConstraintSetPtr &ks,
00044 const constraint_samplers::ConstraintSamplerPtr &cs) :
00045 ob::GoalLazySamples(pc->getOMPLSimpleSetup().getSpaceInformation(), boost::bind(&ConstrainedGoalSampler::sampleUsingConstraintSampler, this, _1, _2), false),
00046 planning_context_(pc),
00047 kinematic_constraint_set_(ks),
00048 constraint_sampler_(cs),
00049 work_state_(pc->getCompleteInitialRobotState()),
00050 work_joint_group_state_(work_state_.getJointStateGroup(planning_context_->getGroupName())),
00051 invalid_sampled_constraints_(0),
00052 warned_invalid_samples_(false),
00053 verbose_display_(0)
00054 {
00055 if (!constraint_sampler_)
00056 default_sampler_ = si_->allocStateSampler();
00057 logDebug("Constructed a ConstrainedGoalSampler instance at address %p", this);
00058 startSampling();
00059 }
00060
00061 bool ompl_interface::ConstrainedGoalSampler::sampleUsingConstraintSampler(const ob::GoalLazySamples *gls, ob::State *newGoal)
00062 {
00063
00064
00065 unsigned int max_attempts = planning_context_->getMaximumGoalSamplingAttempts();
00066 unsigned int attempts_so_far = gls->samplingAttemptsCount();
00067
00068
00069 if (attempts_so_far >= max_attempts)
00070 return false;
00071
00072
00073 if (gls->getStateCount() >= planning_context_->getMaximumGoalSamples())
00074 return false;
00075
00076
00077 if (planning_context_->getOMPLSimpleSetup().getProblemDefinition()->hasSolution())
00078 return false;
00079
00080 unsigned int max_attempts_div2 = max_attempts/2;
00081 for (unsigned int a = gls->samplingAttemptsCount() ; a < max_attempts && gls->isSampling() ; ++a)
00082 {
00083 bool verbose = false;
00084 if (gls->getStateCount() == 0 && a >= max_attempts_div2)
00085 if (verbose_display_ < 1)
00086 {
00087 verbose = true;
00088 verbose_display_++;
00089 }
00090
00091 if (constraint_sampler_)
00092 {
00093 if (constraint_sampler_->project(work_joint_group_state_, planning_context_->getCompleteInitialRobotState(), planning_context_->getMaximumStateSamplingAttempts()))
00094 {
00095 if (kinematic_constraint_set_->decide(work_state_, verbose).satisfied)
00096 {
00097 planning_context_->getOMPLStateSpace()->copyToOMPLState(newGoal, work_joint_group_state_);
00098 if (static_cast<const StateValidityChecker*>(si_->getStateValidityChecker().get())->isValid(newGoal, verbose))
00099 return true;
00100 }
00101 else
00102 {
00103 invalid_sampled_constraints_++;
00104 if (!warned_invalid_samples_ && invalid_sampled_constraints_ >= (attempts_so_far * 8) / 10)
00105 {
00106 warned_invalid_samples_ = true;
00107 logWarn("More than 80%% of the sampled goal states fail to satisfy the constraints imposed on the goal sampler. Is the constrained sampler working correctly?");
00108 }
00109 }
00110 }
00111 }
00112 else
00113 {
00114 default_sampler_->sampleUniform(newGoal);
00115 if (static_cast<const StateValidityChecker*>(si_->getStateValidityChecker().get())->isValid(newGoal, verbose))
00116 {
00117 planning_context_->getOMPLStateSpace()->copyToRobotState(work_joint_group_state_, newGoal);
00118 if (kinematic_constraint_set_->decide(work_state_, verbose).satisfied)
00119 return true;
00120 }
00121 }
00122 }
00123 return false;
00124 }