constrained_valid_state_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_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   //  moveit::Profiler::ScopedBlock pblock("ValidConstrainedSampler::sample");
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 }


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