All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator
RigidBodyPlanningWithIK.cpp
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, Rice University
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 Rice University 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/base/spaces/SE3StateSpace.h>
00038 #include <ompl/geometric/SimpleSetup.h>
00039 #include <ompl/base/GoalLazySamples.h>
00040 #include <ompl/geometric/ik/GAIK.h>
00041 
00042 #include <ompl/config.h>
00043 #include <iostream>
00044 
00045 namespace ob = ompl::base;
00046 namespace og = ompl::geometric;
00047 
00049 // describe an arbitrary representation of a goal region in SE(3)
00050 class MyGoalRegion : public ob::GoalRegion
00051 {
00052 public:
00053 
00054     MyGoalRegion(const ob::SpaceInformationPtr &si) : ob::GoalRegion(si)
00055     {
00056         setThreshold(1e-2);
00057     }
00058 
00059     virtual double distanceGoal(const ob::State *state) const
00060     {
00061         // goal region is given by states where x + y = z and orientation is close to identity
00062         double d = fabs(state->as<ob::SE3StateSpace::StateType>()->getX()
00063                         + state->as<ob::SE3StateSpace::StateType>()->getY()
00064                         - state->as<ob::SE3StateSpace::StateType>()->getZ())
00065             + fabs(state->as<ob::SE3StateSpace::StateType>()->rotation().w - 1.0);
00066         return d;
00067     }
00068 
00069 };
00070 
00071 // Goal regions such as the one above cannot be sampled, so
00072 // bi-directional trees cannot be used for solving. However, we can
00073 // transform such goal regions into ones that can be sampled. The
00074 // caveat is that it should be possible to find states in this region
00075 // with some other algorithm. Genetic algorithms that essentially
00076 // perform inverse kinematics in the general sense can be used:
00077 
00078 bool regionSamplingWithGAIK(const ob::SpaceInformationPtr &si, const ob::GoalRegion *region, const ob::GoalLazySamples *gls, ob::State *result)
00079 {
00080     og::GAIK g(si);
00081     bool cont = g.solve(1.0, *region, result);
00082 
00083     if (cont)
00084     {
00085         std::cout << "Found goal state: " << std::endl;
00086         si->printState(result);
00087     }
00088 
00089     // we continue sampling while we are able to find solutions, we have found not more than 2 previous solutions and we have not yet solved the problem
00090     return cont && gls->maxSampleCount() < 3 && !gls->isAchieved();
00091 }
00092 
00093 void planWithIK(void)
00094 {
00095     // construct the state space we are planning in
00096     ob::StateSpacePtr space(new ob::SE3StateSpace());
00097 
00098     // set the bounds for the R^3 part of SE(3)
00099     ob::RealVectorBounds bounds(3);
00100     bounds.setLow(-1);
00101     bounds.setHigh(1);
00102 
00103     space->as<ob::SE3StateSpace>()->setBounds(bounds);
00104 
00105     // define a simple setup class
00106     og::SimpleSetup ss(space);
00107 
00108     // create a random start state
00109     ob::ScopedState<ob::SE3StateSpace> start(space);
00110     start->setXYZ(0, 0, 0);
00111     start->rotation().setIdentity();
00112     ss.addStartState(start);
00113 
00114     // define our goal region
00115     MyGoalRegion region(ss.getSpaceInformation());
00116 
00117     // bind a sampling function that fills its argument with a sampled state and returns true while it can produce new samples
00118     // we don't need to check if new samples are different from ones previously computed as this is pefromed automatically by GoalLazySamples
00119     ob::GoalSamplingFn samplingFunction = boost::bind(&regionSamplingWithGAIK, ss.getSpaceInformation(), &region, _1, _2);
00120 
00121     // create an instance of GoalLazySamples:
00122     ob::GoalPtr goal(new ob::GoalLazySamples(ss.getSpaceInformation(), samplingFunction));
00123 
00124     // we set a goal that is sampleable, but it in fact corresponds to a region that is not sampleable by default
00125     ss.setGoal(goal);
00126 
00127     // attempt to solve the problem
00128     bool solved = ss.solve(3.0);
00129 
00130     if (solved)
00131     {
00132         std::cout << "Found solution:" << std::endl;
00133         // print the path to screen
00134         ss.simplifySolution();
00135         ss.getSolutionPath().print(std::cout);
00136     }
00137     else
00138         std::cout << "No solution found" << std::endl;
00139 
00140     // the region variable will now go out of scope. To make sure it is not used in the sampling function any more
00141     // (i.e., the sampling thread was able to terminate), we make sure sampling has terminated
00142     goal->as<ob::GoalLazySamples>()->stopSampling();
00143 }
00145 
00146 int main(int, char **)
00147 {
00148     std::cout << "OMPL version: " << OMPL_VERSION << std::endl;
00149 
00150     planWithIK();
00151 
00152     return 0;
00153 }