43                                                        constraint_samplers::ConstraintSamplerPtr cs)
 
   44   : ob::StateSampler(pc->getOMPLStateSpace().get())
 
   45   , planning_context_(pc)
 
   46   , default_(space_->allocDefaultStateSampler())
 
   47   , constraint_sampler_(std::move(cs))
 
   48   , work_state_(pc->getCompleteInitialRobotState())
 
   49   , constrained_success_(0)
 
   50   , constrained_failure_(0)
 
   52   inv_dim_ = space_->getDimension() > 0 ? 1.0 / (double)space_->getDimension() : 1.0;
 
   57   if (constrained_success_ == 0)
 
   60     return (
double)constrained_success_ / (double)(constrained_success_ + constrained_failure_);
 
   63 bool ompl_interface::ConstrainedSampler::sampleC(ob::State* state)
 
   65   if (constraint_sampler_->sample(work_state_, planning_context_->getCompleteInitialRobotState(),
 
   66                                   planning_context_->getMaximumStateSamplingAttempts()))
 
   68     planning_context_->getOMPLStateSpace()->copyToOMPLState(state, work_state_);
 
   69     if (space_->satisfiesBounds(state))
 
   71       ++constrained_success_;
 
   75   ++constrained_failure_;
 
   81   if (!sampleC(state) && !sampleC(state) && !sampleC(state))
 
   82     default_->sampleUniform(state);
 
   88   if (sampleC(state) || sampleC(state) || sampleC(state))
 
   90     double total_d = space_->distance(state, near);
 
   93       double dist = pow(rng_.uniform01(), inv_dim_) * 
distance;
 
   94       space_->interpolate(near, state, dist / total_d, state);
 
   98     default_->sampleUniformNear(state, near, 
distance);
 
  103   if (sampleC(state) || sampleC(state) || sampleC(state))
 
  105     double total_d = space_->distance(state, mean);
 
  106     double distance = rng_.gaussian(0.0, stdDev);
 
  109       double dist = pow(rng_.uniform01(), inv_dim_) * 
distance;
 
  110       space_->interpolate(mean, state, dist / total_d, state);
 
  114     default_->sampleGaussian(state, mean, stdDev);
 
void sampleUniformNear(ompl::base::State *state, const ompl::base::State *near, const double distance) override
Sample a state (uniformly) within a certain distance of another state.
 
double getConstrainedSamplingRate() const
 
void sampleUniform(ompl::base::State *state) override
Sample a state (uniformly)
 
void sampleGaussian(ompl::base::State *state, const ompl::base::State *mean, const double stdDev) override
Sample a state using the specified Gaussian.
 
ConstrainedSampler(const ModelBasedPlanningContext *pc, constraint_samplers::ConstraintSamplerPtr cs)
Default constructor.
 
double distance(const urdf::Pose &transform)