constrained_sampler.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2011, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/ompl_interface/detail/constrained_sampler.h>
00038 #include <moveit/ompl_interface/model_based_planning_context.h>
00039 #include <moveit/profiler/profiler.h>
00040 
00041 ompl_interface::ConstrainedSampler::ConstrainedSampler(const ModelBasedPlanningContext *pc, const constraint_samplers::ConstraintSamplerPtr &cs) :
00042   ob::StateSampler(pc->getOMPLStateSpace().get()), planning_context_(pc), default_(space_->allocDefaultStateSampler()),
00043   constraint_sampler_(cs), work_state_(pc->getCompleteInitialRobotState()),
00044   work_joint_group_state_(work_state_.getJointStateGroup(planning_context_->getGroupName())),
00045   constrained_success_(0), constrained_failure_(0)
00046 {
00047   inv_dim_ = space_->getDimension() > 0 ? 1.0 / (double)space_->getDimension() : 1.0;
00048 }
00049 
00050 double ompl_interface::ConstrainedSampler::getConstrainedSamplingRate() const
00051 {
00052   if (constrained_success_ == 0)
00053     return 0.0;
00054   else
00055     return (double)constrained_success_ / (double)(constrained_success_ + constrained_failure_);
00056 }
00057 
00058 bool ompl_interface::ConstrainedSampler::sampleC(ob::State *state)
00059 {
00060   //  moveit::Profiler::ScopedBlock sblock("sampleWithConstraints");
00061 
00062   if (constraint_sampler_->sample(work_joint_group_state_, planning_context_->getCompleteInitialRobotState(), planning_context_->getMaximumStateSamplingAttempts()))
00063   {
00064     planning_context_->getOMPLStateSpace()->copyToOMPLState(state, work_joint_group_state_);
00065     if (space_->satisfiesBounds(state))
00066     {
00067       ++constrained_success_;
00068       return true;
00069     }
00070   }
00071   ++constrained_failure_;
00072   return false;
00073 }
00074 
00075 void ompl_interface::ConstrainedSampler::sampleUniform(ob::State *state)
00076 {
00077   if (!sampleC(state) && !sampleC(state) && !sampleC(state))
00078     default_->sampleUniform(state);
00079 }
00080 
00081 void ompl_interface::ConstrainedSampler::sampleUniformNear(ob::State *state, const ob::State *near, const double distance)
00082 {
00083   if (sampleC(state) || sampleC(state) || sampleC(state))
00084   {
00085     double total_d = space_->distance(state, near);
00086     if (total_d > distance)
00087     {
00088       double dist = pow(rng_.uniform01(), inv_dim_) * distance;
00089       space_->interpolate(near, state, dist / total_d, state);
00090     }
00091   }
00092   else
00093     default_->sampleUniformNear(state, near, distance);
00094 }
00095 
00096 void ompl_interface::ConstrainedSampler::sampleGaussian(ob::State *state, const ob::State *mean, const double stdDev)
00097 {
00098   if (sampleC(state) || sampleC(state) || sampleC(state))
00099   {
00100     double total_d = space_->distance(state, mean);
00101     double distance = rng_.gaussian(0.0, stdDev);
00102     if (total_d > distance)
00103     {
00104       double dist = pow(rng_.uniform01(), inv_dim_) * distance;
00105       space_->interpolate(mean, state, dist / total_d, state);
00106     }
00107   }
00108   else
00109     default_->sampleGaussian(state, mean, stdDev);
00110 }


ompl
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 11:12:03