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_valid_state_sampler.h>
00038 #include <moveit/ompl_interface/model_based_planning_context.h>
00039 #include <moveit/profiler/profiler.h>
00040
00041 ompl_interface::ValidConstrainedSampler::ValidConstrainedSampler(const ModelBasedPlanningContext *pc,
00042 const kinematic_constraints::KinematicConstraintSetPtr &ks,
00043 const constraint_samplers::ConstraintSamplerPtr &cs)
00044 : ob::ValidStateSampler(pc->getOMPLSimpleSetup()->getSpaceInformation().get())
00045 , planning_context_(pc)
00046 , kinematic_constraint_set_(ks)
00047 , constraint_sampler_(cs)
00048 , work_state_(pc->getCompleteInitialRobotState())
00049 {
00050 if (!constraint_sampler_)
00051 default_sampler_ = si_->allocStateSampler();
00052 inv_dim_ = si_->getStateSpace()->getDimension() > 0 ? 1.0 / (double)si_->getStateSpace()->getDimension() : 1.0;
00053 logDebug("Constructed a ValidConstrainedSampler instance at address %p", this);
00054 }
00055
00056 bool ompl_interface::ValidConstrainedSampler::project(ompl::base::State *state)
00057 {
00058 if (constraint_sampler_)
00059 {
00060 planning_context_->getOMPLStateSpace()->copyToRobotState(work_state_, state);
00061 if (constraint_sampler_->project(work_state_, planning_context_->getMaximumStateSamplingAttempts()))
00062 {
00063 if (kinematic_constraint_set_->decide(work_state_).satisfied)
00064 {
00065 planning_context_->getOMPLStateSpace()->copyToOMPLState(state, work_state_);
00066 return true;
00067 }
00068 }
00069 }
00070 return false;
00071 }
00072
00073 bool ompl_interface::ValidConstrainedSampler::sample(ob::State *state)
00074 {
00075
00076 if (constraint_sampler_)
00077 {
00078 if (constraint_sampler_->sample(work_state_, planning_context_->getCompleteInitialRobotState(), planning_context_->getMaximumStateSamplingAttempts()))
00079 {
00080 if (kinematic_constraint_set_->decide(work_state_).satisfied)
00081 {
00082 planning_context_->getOMPLStateSpace()->copyToOMPLState(state, work_state_);
00083 return true;
00084 }
00085 }
00086 }
00087 else
00088 {
00089 default_sampler_->sampleUniform(state);
00090 planning_context_->getOMPLStateSpace()->copyToRobotState(work_state_, state);
00091 if (kinematic_constraint_set_->decide(work_state_).satisfied)
00092 return true;
00093 }
00094
00095 return false;
00096 }
00097
00098 bool ompl_interface::ValidConstrainedSampler::sampleNear(ompl::base::State *state, const ompl::base::State *near, const double distance)
00099 {
00100 if (!sample(state))
00101 return false;
00102 double total_d = si_->distance(state, near);
00103 if (total_d > distance)
00104 {
00105 double dist = pow(rng_.uniform01(), inv_dim_) * distance;
00106 si_->getStateSpace()->interpolate(near, state, dist / total_d, state);
00107 planning_context_->getOMPLStateSpace()->copyToRobotState(work_state_, state);
00108 if (!kinematic_constraint_set_->decide(work_state_).satisfied)
00109 return false;
00110 }
00111 return true;
00112 }