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 /
static_cast<double>(space_->getDimension()) : 1.0;
57 if (constrained_success_ == 0)
63 return static_cast<double>(constrained_success_) /
static_cast<double>(constrained_success_ + constrained_failure_);
67bool ompl_interface::ConstrainedSampler::sampleC(ob::State* state)
69 if (constraint_sampler_->sample(work_state_, planning_context_->getCompleteInitialRobotState(),
70 planning_context_->getMaximumStateSamplingAttempts()))
72 planning_context_->getOMPLStateSpace()->copyToOMPLState(state, work_state_);
73 if (space_->satisfiesBounds(state))
75 ++constrained_success_;
79 ++constrained_failure_;
85 if (!sampleC(state) && !sampleC(state) && !sampleC(state))
86 default_->sampleUniform(state);
90 const double distance)
92 if (sampleC(state) || sampleC(state) || sampleC(state))
94 double total_d = space_->distance(state, near);
95 if (total_d > distance)
97 double dist = pow(rng_.uniform01(), inv_dim_) * distance;
98 space_->interpolate(near, state, dist / total_d, state);
102 default_->sampleUniformNear(state, near, distance);
107 if (sampleC(state) || sampleC(state) || sampleC(state))
109 double total_d = space_->distance(state, mean);
110 double distance = rng_.gaussian(0.0, stdDev);
111 if (total_d > distance)
113 double dist = pow(rng_.uniform01(), inv_dim_) * distance;
114 space_->interpolate(mean, state, dist / total_d, state);
118 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.