ompl/geometric/planners/rrt/src/pRRT.cpp
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, 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 "ompl/geometric/planners/rrt/pRRT.h"
00038 #include "ompl/base/goals/GoalSampleableRegion.h"
00039 #include "ompl/tools/config/SelfConfig.h"
00040 #include <boost/thread/thread.hpp>
00041 #include <limits>
00042 
00043 ompl::geometric::pRRT::pRRT(const base::SpaceInformationPtr &si) : base::Planner(si, "pRRT"),
00044                                                                   samplerArray_(si)
00045 {
00046     specs_.approximateSolutions = true;
00047     specs_.multithreaded = true;
00048     specs_.directed = true;
00049 
00050     setThreadCount(2);
00051     goalBias_ = 0.05;
00052     maxDistance_ = 0.0;
00053     lastGoalMotion_ = NULL;
00054 
00055     Planner::declareParam<double>("range", this, &pRRT::setRange, &pRRT::getRange, "0.:1.:10000.");
00056     Planner::declareParam<double>("goal_bias", this, &pRRT::setGoalBias, &pRRT::getGoalBias, "0.:.05:1.");
00057     Planner::declareParam<unsigned int>("thread_count", this, &pRRT::setThreadCount, &pRRT::getThreadCount, "1:64");
00058 }
00059 
00060 ompl::geometric::pRRT::~pRRT()
00061 {
00062     freeMemory();
00063 }
00064 
00065 void ompl::geometric::pRRT::setup()
00066 {
00067     Planner::setup();
00068     tools::SelfConfig sc(si_, getName());
00069     sc.configurePlannerRange(maxDistance_);
00070 
00071     if (!nn_)
00072         nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion*>(si_->getStateSpace()));
00073     nn_->setDistanceFunction(boost::bind(&pRRT::distanceFunction, this, _1, _2));
00074 }
00075 
00076 void ompl::geometric::pRRT::clear()
00077 {
00078     Planner::clear();
00079     samplerArray_.clear();
00080     freeMemory();
00081     if (nn_)
00082         nn_->clear();
00083     lastGoalMotion_ = NULL;
00084 }
00085 
00086 void ompl::geometric::pRRT::freeMemory()
00087 {
00088     if (nn_)
00089     {
00090         std::vector<Motion*> motions;
00091         nn_->list(motions);
00092         for (unsigned int i = 0 ; i < motions.size() ; ++i)
00093         {
00094             if (motions[i]->state)
00095                 si_->freeState(motions[i]->state);
00096             delete motions[i];
00097         }
00098     }
00099 }
00100 
00101 void ompl::geometric::pRRT::threadSolve(unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol)
00102 {
00103     base::Goal                 *goal   = pdef_->getGoal().get();
00104     base::GoalSampleableRegion *goal_s = dynamic_cast<base::GoalSampleableRegion*>(goal);
00105     RNG                         rng;
00106 
00107     Motion *rmotion   = new Motion(si_);
00108     base::State *rstate = rmotion->state;
00109     base::State *xstate = si_->allocState();
00110 
00111     while (sol->solution == NULL && ptc == false)
00112     {
00113         /* sample random state (with goal biasing) */
00114         if (goal_s && rng.uniform01() < goalBias_ && goal_s->canSample())
00115             goal_s->sampleGoal(rstate);
00116         else
00117             samplerArray_[tid]->sampleUniform(rstate);
00118 
00119         /* find closest state in the tree */
00120         nnLock_.lock();
00121         Motion *nmotion = nn_->nearest(rmotion);
00122         nnLock_.unlock();
00123         base::State *dstate = rstate;
00124 
00125         /* find state to add */
00126         double d = si_->distance(nmotion->state, rstate);
00127         if (d > maxDistance_)
00128         {
00129             si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
00130             dstate = xstate;
00131         }
00132 
00133         if (si_->checkMotion(nmotion->state, dstate))
00134         {
00135             /* create a motion */
00136             Motion *motion = new Motion(si_);
00137             si_->copyState(motion->state, dstate);
00138             motion->parent = nmotion;
00139 
00140             nnLock_.lock();
00141             nn_->add(motion);
00142             nnLock_.unlock();
00143 
00144             double dist = 0.0;
00145             bool solved = goal->isSatisfied(motion->state, &dist);
00146             if (solved)
00147             {
00148                 sol->lock.lock();
00149                 sol->approxdif = dist;
00150                 sol->solution = motion;
00151                 sol->lock.unlock();
00152                 break;
00153             }
00154             if (dist < sol->approxdif)
00155             {
00156                 sol->lock.lock();
00157                 if (dist < sol->approxdif)
00158                 {
00159                     sol->approxdif = dist;
00160                     sol->approxsol = motion;
00161                 }
00162                 sol->lock.unlock();
00163             }
00164         }
00165     }
00166 
00167     si_->freeState(xstate);
00168     if (rmotion->state)
00169         si_->freeState(rmotion->state);
00170     delete rmotion;
00171 }
00172 
00173 ompl::base::PlannerStatus ompl::geometric::pRRT::solve(const base::PlannerTerminationCondition &ptc)
00174 {
00175     checkValidity();
00176 
00177     base::GoalRegion *goal = dynamic_cast<base::GoalRegion*>(pdef_->getGoal().get());
00178 
00179     if (!goal)
00180     {
00181         OMPL_ERROR("%s: Unknow type of goal", getName().c_str());
00182         return base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE;
00183     }
00184 
00185     samplerArray_.resize(threadCount_);
00186 
00187     while (const base::State *st = pis_.nextStart())
00188     {
00189         Motion *motion = new Motion(si_);
00190         si_->copyState(motion->state, st);
00191         nn_->add(motion);
00192     }
00193 
00194     if (nn_->size() == 0)
00195     {
00196         OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
00197         return base::PlannerStatus::INVALID_START;
00198     }
00199 
00200     OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
00201 
00202     SolutionInfo sol;
00203     sol.solution = NULL;
00204     sol.approxsol = NULL;
00205     sol.approxdif = std::numeric_limits<double>::infinity();
00206 
00207     std::vector<boost::thread*> th(threadCount_);
00208     for (unsigned int i = 0 ; i < threadCount_ ; ++i)
00209         th[i] = new boost::thread(boost::bind(&pRRT::threadSolve, this, i, ptc, &sol));
00210     for (unsigned int i = 0 ; i < threadCount_ ; ++i)
00211     {
00212         th[i]->join();
00213         delete th[i];
00214     }
00215 
00216     bool solved = false;
00217     bool approximate = false;
00218     if (sol.solution == NULL)
00219     {
00220         sol.solution = sol.approxsol;
00221         approximate = true;
00222     }
00223 
00224     if (sol.solution != NULL)
00225     {
00226         lastGoalMotion_ = sol.solution;
00227 
00228         /* construct the solution path */
00229         std::vector<Motion*> mpath;
00230         while (sol.solution != NULL)
00231         {
00232             mpath.push_back(sol.solution);
00233             sol.solution = sol.solution->parent;
00234         }
00235 
00236         /* set the solution path */
00237         PathGeometric *path = new PathGeometric(si_);
00238            for (int i = mpath.size() - 1 ; i >= 0 ; --i)
00239             path->append(mpath[i]->state);
00240 
00241         pdef_->addSolutionPath(base::PathPtr(path), approximate, sol.approxdif, getName());
00242         solved = true;
00243     }
00244 
00245     OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
00246 
00247     return base::PlannerStatus(solved, approximate);
00248 }
00249 
00250 void ompl::geometric::pRRT::getPlannerData(base::PlannerData &data) const
00251 {
00252     Planner::getPlannerData(data);
00253 
00254     std::vector<Motion*> motions;
00255     if (nn_)
00256         nn_->list(motions);
00257 
00258     if (lastGoalMotion_)
00259         data.addGoalVertex(base::PlannerDataVertex(lastGoalMotion_->state));
00260 
00261     for (unsigned int i = 0 ; i < motions.size() ; ++i)
00262     {
00263         if (motions[i]->parent == NULL)
00264             data.addStartVertex(base::PlannerDataVertex(motions[i]->state));
00265         else
00266             data.addEdge(base::PlannerDataVertex(motions[i]->parent->state),
00267                          base::PlannerDataVertex(motions[i]->state));
00268     }
00269 }
00270 
00271 void ompl::geometric::pRRT::setThreadCount(unsigned int nthreads)
00272 {
00273     assert(nthreads > 0);
00274     threadCount_ = nthreads;
00275 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines