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/SpaceInformation.h> 00038 #include <ompl/base/spaces/SE3StateSpace.h> 00039 #include <ompl/geometric/planners/rrt/RRTConnect.h> 00040 #include <ompl/geometric/SimpleSetup.h> 00041 00042 #include <ompl/config.h> 00043 #include <iostream> 00044 00045 namespace ob = ompl::base; 00046 namespace og = ompl::geometric; 00047 00048 bool isStateValid(const ob::State *state) 00049 { 00050 // cast the abstract state type to the type we expect 00051 const ob::SE3StateSpace::StateType *se3state = state->as<ob::SE3StateSpace::StateType>(); 00052 00053 // extract the first component of the state and cast it to what we expect 00054 const ob::RealVectorStateSpace::StateType *pos = se3state->as<ob::RealVectorStateSpace::StateType>(0); 00055 00056 // extract the second component of the state and cast it to what we expect 00057 const ob::SO3StateSpace::StateType *rot = se3state->as<ob::SO3StateSpace::StateType>(1); 00058 00059 // check validity of state defined by pos & rot 00060 00061 00062 // return a value that is always true but uses the two variables we define, so we avoid compiler warnings 00063 return (void*)rot != (void*)pos; 00064 } 00065 00066 void plan(void) 00067 { 00068 // construct the state space we are planning in 00069 ob::StateSpacePtr space(new ob::SE3StateSpace()); 00070 00071 // set the bounds for the R^3 part of SE(3) 00072 ob::RealVectorBounds bounds(3); 00073 bounds.setLow(-1); 00074 bounds.setHigh(1); 00075 00076 space->as<ob::SE3StateSpace>()->setBounds(bounds); 00077 00078 // construct an instance of space information from this state space 00079 ob::SpaceInformationPtr si(new ob::SpaceInformation(space)); 00080 00081 // set state validity checking for this space 00082 si->setStateValidityChecker(boost::bind(&isStateValid, _1)); 00083 00084 // create a random start state 00085 ob::ScopedState<> start(space); 00086 start.random(); 00087 00088 // create a random goal state 00089 ob::ScopedState<> goal(space); 00090 goal.random(); 00091 00092 // create a problem instance 00093 ob::ProblemDefinitionPtr pdef(new ob::ProblemDefinition(si)); 00094 00095 // set the start and goal states 00096 pdef->setStartAndGoalStates(start, goal); 00097 00098 // create a planner for the defined space 00099 ob::PlannerPtr planner(new og::RRTConnect(si)); 00100 00101 // set the problem we are trying to solve for the planner 00102 planner->setProblemDefinition(pdef); 00103 00104 // perform setup steps for the planner 00105 planner->setup(); 00106 00107 00108 // print the settings for this space 00109 si->printSettings(std::cout); 00110 00111 // print the problem settings 00112 pdef->print(std::cout); 00113 00114 // attempt to solve the problem within one second of planning time 00115 bool solved = planner->solve(1.0); 00116 00117 if (solved) 00118 { 00119 // get the goal representation from the problem definition (not the same as the goal state) 00120 // and inquire about the found path 00121 ob::PathPtr path = pdef->getGoal()->getSolutionPath(); 00122 std::cout << "Found solution:" << std::endl; 00123 00124 // print the path to screen 00125 path->print(std::cout); 00126 } 00127 else 00128 std::cout << "No solution found" << std::endl; 00129 } 00130 00131 void planWithSimpleSetup(void) 00132 { 00133 // construct the state space we are planning in 00134 ob::StateSpacePtr space(new ob::SE3StateSpace()); 00135 00136 // set the bounds for the R^3 part of SE(3) 00137 ob::RealVectorBounds bounds(3); 00138 bounds.setLow(-1); 00139 bounds.setHigh(1); 00140 00141 space->as<ob::SE3StateSpace>()->setBounds(bounds); 00142 00143 // define a simple setup class 00144 og::SimpleSetup ss(space); 00145 00146 // set state validity checking for this space 00147 ss.setStateValidityChecker(boost::bind(&isStateValid, _1)); 00148 00149 // create a random start state 00150 ob::ScopedState<> start(space); 00151 start.random(); 00152 00153 // create a random goal state 00154 ob::ScopedState<> goal(space); 00155 goal.random(); 00156 00157 // set the start and goal states 00158 ss.setStartAndGoalStates(start, goal); 00159 00160 // attempt to solve the problem within one second of planning time 00161 bool solved = ss.solve(1.0); 00162 00163 if (solved) 00164 { 00165 std::cout << "Found solution:" << std::endl; 00166 // print the path to screen 00167 ss.simplifySolution(); 00168 ss.getSolutionPath().print(std::cout); 00169 } 00170 else 00171 std::cout << "No solution found" << std::endl; 00172 } 00173 00174 int main(int, char **) 00175 { 00176 std::cout << "ompl version: " << OMPL_VERSION << std::endl; 00177 00178 plan(); 00179 00180 std::cout << std::endl << std::endl; 00181 00182 planWithSimpleSetup(); 00183 00184 return 0; 00185 }