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/base/SpaceInformation.h>
00038 #include <ompl/base/spaces/SE3StateSpace.h>
00039 #include <ompl/base/samplers/ObstacleBasedValidStateSampler.h>
00040 #include <ompl/geometric/planners/rrt/RRTConnect.h>
00041 #include <ompl/geometric/SimpleSetup.h>
00042
00043 #include <ompl/config.h>
00044 #include <boost/thread.hpp>
00045 #include <iostream>
00046
00047 namespace ob = ompl::base;
00048 namespace og = ompl::geometric;
00049
00050
00051
00052
00053
00054
00055
00056 class MyValidStateSampler : public ob::ValidStateSampler
00057 {
00058 public:
00059 MyValidStateSampler(const ob::SpaceInformation *si) : ValidStateSampler(si)
00060 {
00061 name_ = "my sampler";
00062 }
00063
00064
00065
00066
00067 virtual bool sample(ob::State *state)
00068 {
00069 double* val = static_cast<ob::RealVectorStateSpace::StateType*>(state)->values;
00070 double z = rng_.uniformReal(-1,1);
00071
00072 if (z>.25 && z<.5)
00073 {
00074 double x = rng_.uniformReal(0,1.8), y = rng_.uniformReal(0,.2);
00075 switch(rng_.uniformInt(0,3))
00076 {
00077 case 0: val[0]=x-1; val[1]=y-1;
00078 case 1: val[0]=x-.8; val[1]=y+.8;
00079 case 2: val[0]=y-1; val[1]=x-1;
00080 case 3: val[0]=y+.8; val[1]=x-.8;
00081 }
00082 }
00083 else
00084 {
00085 val[0] = rng_.uniformReal(-1,1);
00086 val[1] = rng_.uniformReal(-1,1);
00087 }
00088 val[2] = z;
00089 assert(si_->isValid(state));
00090 return true;
00091 }
00092
00093 virtual bool sampleNear(ob::State *state, const ob::State *near, const double distance)
00094 {
00095 throw ompl::Exception("MyValidStateSampler::sampleNear", "not implemented");
00096 return false;
00097 }
00098 protected:
00099 ompl::RNG rng_;
00100 };
00101
00102
00103
00104 bool isStateValid(const ob::State *state)
00105 {
00106 const ob::RealVectorStateSpace::StateType& pos = *state->as<ob::RealVectorStateSpace::StateType>();
00107
00108
00109
00110 boost::this_thread::sleep(ompl::time::seconds(.001));
00111
00112
00113
00114 return !(fabs(pos[0]<.8) && fabs(pos[1]<.8) && pos[2]>.25 && pos[2]<.5);
00115 }
00116
00117
00118 ob::ValidStateSamplerPtr allocOBValidStateSampler(const ob::SpaceInformation *si)
00119 {
00120
00121
00122 return ob::ValidStateSamplerPtr(new ob::ObstacleBasedValidStateSampler(si));
00123 }
00124
00125
00126 ob::ValidStateSamplerPtr allocMyValidStateSampler(const ob::SpaceInformation *si)
00127 {
00128 return ob::ValidStateSamplerPtr(new MyValidStateSampler(si));
00129 }
00130
00131
00132 void plan(int samplerIndex)
00133 {
00134
00135 ob::StateSpacePtr space(new ob::RealVectorStateSpace(3));
00136
00137
00138 ob::RealVectorBounds bounds(3);
00139 bounds.setLow(-1);
00140 bounds.setHigh(1);
00141 space->as<ob::RealVectorStateSpace>()->setBounds(bounds);
00142
00143
00144 og::SimpleSetup ss(space);
00145
00146
00147 ss.setStateValidityChecker(boost::bind(&isStateValid, _1));
00148
00149
00150 ob::ScopedState<> start(space);
00151 start[0] = start[1] = start[2] = 0;
00152
00153
00154 ob::ScopedState<> goal(space);
00155 goal[0] = goal[1] = 0.;
00156 goal[2] = 1;
00157
00158
00159 ss.setStartAndGoalStates(start, goal);
00160
00161
00162 if (samplerIndex==1)
00163
00164 ss.getSpaceInformation()->setValidStateSamplerAllocator(allocOBValidStateSampler);
00165 else if (samplerIndex==2)
00166
00167 ss.getSpaceInformation()->setValidStateSamplerAllocator(allocMyValidStateSampler);
00168
00169
00170
00171 ob::PlannerPtr planner(new og::RRTConnect(ss.getSpaceInformation()));
00172 ss.setPlanner(planner);
00173
00174
00175 bool solved = ss.solve(10.0);
00176 if (solved)
00177 {
00178 std::cout << "Found solution:" << std::endl;
00179
00180 ss.simplifySolution();
00181 ss.getSolutionPath().print(std::cout);
00182 }
00183 else
00184 std::cout << "No solution found" << std::endl;
00185 }
00186
00187 int main(int, char **)
00188 {
00189 std::cout << "Using default uniform sampler:" << std::endl;
00190 plan(0);
00191 std::cout << "\nUsing obstacle-based sampler:" << std::endl;
00192 plan(1);
00193 std::cout << "\nUsing my sampler:" << std::endl;
00194 plan(2);
00195
00196 return 0;
00197 }