demos/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/goals/GoalLazySamples.h> 00040 #include <ompl/geometric/GeneticSearch.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 regionSamplingWithGS(const ob::SpaceInformationPtr &si, const ob::ProblemDefinitionPtr &pd, const ob::GoalRegion *region, const ob::GoalLazySamples *gls, ob::State *result) 00079 { 00080 og::GeneticSearch g(si); 00081 00082 // we can use a larger time duration for solve(), but we want to demo the ability 00083 // of GeneticSearch to continue from where it left off 00084 bool cont = false; 00085 for (int i = 0 ; i < 100 ; ++i) 00086 if (g.solve(0.05, *region, result)) 00087 { 00088 cont = true; 00089 break; 00090 } 00091 00092 if (cont) 00093 { 00094 std::cout << "Found goal state: " << std::endl; 00095 si->printState(result); 00096 } 00097 00098 // 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 00099 return cont && gls->maxSampleCount() < 3 && !pd->hasSolution(); 00100 } 00101 00102 void planWithIK(void) 00103 { 00104 // construct the state space we are planning in 00105 ob::StateSpacePtr space(new ob::SE3StateSpace()); 00106 00107 // set the bounds for the R^3 part of SE(3) 00108 ob::RealVectorBounds bounds(3); 00109 bounds.setLow(-1); 00110 bounds.setHigh(1); 00111 00112 space->as<ob::SE3StateSpace>()->setBounds(bounds); 00113 00114 // define a simple setup class 00115 og::SimpleSetup ss(space); 00116 00117 // create a random start state 00118 ob::ScopedState<ob::SE3StateSpace> start(space); 00119 start->setXYZ(0, 0, 0); 00120 start->rotation().setIdentity(); 00121 ss.addStartState(start); 00122 00123 // define our goal region 00124 MyGoalRegion region(ss.getSpaceInformation()); 00125 00126 // bind a sampling function that fills its argument with a sampled state and returns true while it can produce new samples 00127 // we don't need to check if new samples are different from ones previously computed as this is pefromed automatically by GoalLazySamples 00128 ob::GoalSamplingFn samplingFunction = boost::bind(®ionSamplingWithGS, ss.getSpaceInformation(), ss.getProblemDefinition(), ®ion, _1, _2); 00129 00130 // create an instance of GoalLazySamples: 00131 ob::GoalPtr goal(new ob::GoalLazySamples(ss.getSpaceInformation(), samplingFunction)); 00132 00133 // we set a goal that is sampleable, but it in fact corresponds to a region that is not sampleable by default 00134 ss.setGoal(goal); 00135 00136 // attempt to solve the problem 00137 ob::PlannerStatus solved = ss.solve(3.0); 00138 00139 if (solved) 00140 { 00141 std::cout << "Found solution:" << std::endl; 00142 // print the path to screen 00143 ss.simplifySolution(); 00144 ss.getSolutionPath().print(std::cout); 00145 } 00146 else 00147 std::cout << "No solution found" << std::endl; 00148 00149 // the region variable will now go out of scope. To make sure it is not used in the sampling function any more 00150 // (i.e., the sampling thread was able to terminate), we make sure sampling has terminated 00151 goal->as<ob::GoalLazySamples>()->stopSampling(); 00152 } 00154 00155 int main(int, char **) 00156 { 00157 std::cout << "OMPL version: " << OMPL_VERSION << std::endl; 00158 00159 planWithIK(); 00160 00161 return 0; 00162 }