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