00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <ompl/control/SpaceInformation.h>
00038 #include <ompl/base/GoalState.h>
00039 #include <ompl/base/spaces/SE2StateSpace.h>
00040 #include <ompl/control/spaces/RealVectorControlSpace.h>
00041 #include <ompl/control/planners/kpiece/KPIECE1.h>
00042 #include <ompl/control/planners/rrt/RRT.h>
00043 #include <ompl/control/SimpleSetup.h>
00044 #include <ompl/config.h>
00045 #include <iostream>
00046
00047 namespace ob = ompl::base;
00048 namespace oc = ompl::control;
00049
00050 bool isStateValid(const oc::SpaceInformation *si, const ob::State *state)
00051 {
00052
00053
00054 const ob::SE2StateSpace::StateType *se2state = state->as<ob::SE2StateSpace::StateType>();
00055
00056
00057 const ob::RealVectorStateSpace::StateType *pos = se2state->as<ob::RealVectorStateSpace::StateType>(0);
00058
00059
00060 const ob::SO2StateSpace::StateType *rot = se2state->as<ob::SO2StateSpace::StateType>(1);
00061
00062
00063
00064
00065
00066 return si->satisfiesBounds(state) && (void*)rot != (void*)pos;
00067 }
00068
00069 void propagate(const ob::State *start, const oc::Control *control, const double duration, ob::State *result)
00070 {
00071 const ob::SE2StateSpace::StateType *se2state = start->as<ob::SE2StateSpace::StateType>();
00072 const ob::RealVectorStateSpace::StateType *pos = se2state->as<ob::RealVectorStateSpace::StateType>(0);
00073 const ob::SO2StateSpace::StateType *rot = se2state->as<ob::SO2StateSpace::StateType>(1);
00074 const oc::RealVectorControlSpace::ControlType *rctrl = control->as<oc::RealVectorControlSpace::ControlType>();
00075
00076 result->as<ob::SE2StateSpace::StateType>()->as<ob::RealVectorStateSpace::StateType>(0)->values[0] =
00077 (*pos)[0] + (*rctrl)[0] * duration * cos(rot->value);
00078
00079 result->as<ob::SE2StateSpace::StateType>()->as<ob::RealVectorStateSpace::StateType>(0)->values[1] =
00080 (*pos)[1] + (*rctrl)[0] * duration * sin(rot->value);
00081
00082 result->as<ob::SE2StateSpace::StateType>()->as<ob::SO2StateSpace::StateType>(1)->value =
00083 rot->value + (*rctrl)[1];
00084 }
00085
00086 void plan(void)
00087 {
00088
00089
00090 ob::StateSpacePtr space(new ob::SE2StateSpace());
00091
00092
00093 ob::RealVectorBounds bounds(2);
00094 bounds.setLow(-1);
00095 bounds.setHigh(1);
00096
00097 space->as<ob::SE2StateSpace>()->setBounds(bounds);
00098
00099
00100 oc::ControlSpacePtr cspace(new oc::RealVectorControlSpace(space, 2));
00101
00102
00103 ob::RealVectorBounds cbounds(2);
00104 cbounds.setLow(-0.3);
00105 cbounds.setHigh(0.3);
00106
00107 cspace->as<oc::RealVectorControlSpace>()->setBounds(cbounds);
00108
00109
00110 cspace->setPropagationFunction(boost::bind(&propagate, _1, _2, _3, _4));
00111
00112
00113 oc::SpaceInformationPtr si(new oc::SpaceInformation(space, cspace));
00114
00115
00116 si->setStateValidityChecker(boost::bind(&isStateValid, si.get(), _1));
00117
00118
00119 ob::ScopedState<ob::SE2StateSpace> start(space);
00120 start->setX(-0.5);
00121 start->setY(0.0);
00122 start->setYaw(0.0);
00123
00124
00125 ob::ScopedState<ob::SE2StateSpace> goal(start);
00126 goal->setX(0.5);
00127
00128
00129 ob::ProblemDefinitionPtr pdef(new ob::ProblemDefinition(si));
00130
00131
00132 pdef->setStartAndGoalStates(start, goal, 0.1);
00133
00134
00135 ob::PlannerPtr planner(new oc::KPIECE1(si));
00136
00137
00138 planner->setProblemDefinition(pdef);
00139
00140
00141 planner->setup();
00142
00143
00144
00145 si->printSettings(std::cout);
00146
00147
00148 pdef->print(std::cout);
00149
00150
00151 bool solved = planner->solve(10.0);
00152
00153 if (solved)
00154 {
00155
00156
00157 ob::PathPtr path = pdef->getGoal()->getSolutionPath();
00158 std::cout << "Found solution:" << std::endl;
00159
00160
00161 path->print(std::cout);
00162 }
00163 else
00164 std::cout << "No solution found" << std::endl;
00165 }
00166
00167
00168 void planWithSimpleSetup(void)
00169 {
00170
00171 ob::StateSpacePtr space(new ob::SE2StateSpace());
00172
00173
00174 ob::RealVectorBounds bounds(2);
00175 bounds.setLow(-1);
00176 bounds.setHigh(1);
00177
00178 space->as<ob::SE2StateSpace>()->setBounds(bounds);
00179
00180
00181 oc::ControlSpacePtr cspace(new oc::RealVectorControlSpace(space, 2));
00182
00183
00184 ob::RealVectorBounds cbounds(2);
00185 cbounds.setLow(-0.3);
00186 cbounds.setHigh(0.3);
00187
00188 cspace->as<oc::RealVectorControlSpace>()->setBounds(cbounds);
00189
00190
00191 cspace->setPropagationFunction(boost::bind(&propagate, _1, _2, _3, _4));
00192
00193
00194 oc::SimpleSetup ss(cspace);
00195
00196
00197 ss.setStateValidityChecker(boost::bind(&isStateValid, ss.getSpaceInformation().get(), _1));
00198
00199
00200 ob::ScopedState<ob::SE2StateSpace> start(space);
00201 start->setX(-0.5);
00202 start->setY(0.0);
00203 start->setYaw(0.0);
00204
00205
00206 ob::ScopedState<ob::SE2StateSpace> goal(space);
00207 (*goal)[0]->as<ob::RealVectorStateSpace::StateType>()->values[0] = 0.0;
00208 (*goal)[0]->as<ob::RealVectorStateSpace::StateType>()->values[1] = 0.5;
00209 (*goal)[1]->as<ob::SO2StateSpace::StateType>()->value = 0.0;
00210
00211
00212
00213 ss.setStartAndGoalStates(start, goal, 0.05);
00214
00215
00216 bool solved = ss.solve(10.0);
00217
00218 if (solved)
00219 {
00220 std::cout << "Found solution:" << std::endl;
00221
00222
00223 ss.getSolutionPath().asGeometric().print(std::cout);
00224 }
00225 else
00226 std::cout << "No solution found" << std::endl;
00227 }
00228
00229 int main(int, char **)
00230 {
00231 std::cout << "ompl version: " << OMPL_VERSION << std::endl;
00232
00233 plan();
00234
00235 std::cout << std::endl << std::endl;
00236
00237 planWithSimpleSetup();
00238
00239 return 0;
00240 }