37#include <ompl/base/spaces/RealVectorStateSpace.h>
38#include <ompl/tools/thunder/Thunder.h>
39#include <ompl/tools/lightning/Lightning.h>
40#include <ompl/util/PPM.h>
42#include <ompl/config.h>
51class Plane2DEnvironment
54 Plane2DEnvironment(
const char *ppm_file,
bool useThunder =
true)
59 ppm_.loadFile(ppm_file);
62 catch (ompl::Exception &ex)
64 OMPL_ERROR(
"Unable to load %s.\n%s", ppm_file, ex.what());
68 auto space(std::make_shared<ob::RealVectorStateSpace>());
69 space->addDimension(0.0, ppm_.getWidth());
70 space->addDimension(0.0, ppm_.getHeight());
71 maxWidth_ = ppm_.getWidth() - 1;
72 maxHeight_ = ppm_.getHeight() - 1;
75 expPlanner_ = std::make_shared<ot::Thunder>(space);
76 expPlanner_->setFilePath(
"thunder.db");
80 expPlanner_ = std::make_shared<ot::Lightning>(space);
81 expPlanner_->setFilePath(
"lightning.db");
84 expPlanner_->setStateValidityChecker([
this](
const ob::State *state) {
return isStateValid(state); });
86 expPlanner_->getSpaceInformation()->setStateValidityCheckingResolution(1.0 / space->getMaximumExtent());
87 vss_ = expPlanner_->getSpaceInformation()->allocValidStateSampler();
103 std::cout << std::endl;
104 std::cout <<
"-------------------------------------------------------" << std::endl;
105 std::cout <<
"-------------------------------------------------------" << std::endl;
112 expPlanner_->clear();
114 ob::ScopedState<> start(expPlanner_->getStateSpace());
115 vss_->sample(start.get());
116 ob::ScopedState<> goal(expPlanner_->getStateSpace());
117 vss_->sample(goal.get());
118 expPlanner_->setStartAndGoalStates(start, goal);
120 bool solved = expPlanner_->solve(10.);
122 OMPL_INFORM(
"Found solution in %g seconds", expPlanner_->getLastPlanComputationTime());
126 expPlanner_->doPostProcessing();
132 bool isStateValid(
const ob::State *state)
const
137 const ompl::PPM::Color &c = ppm_.getPixel(h, w);
138 return c.red > 127 && c.green > 127 && c.blue > 127;
141 ot::ExperienceSetupPtr expPlanner_;
142 ob::ValidStateSamplerPtr vss_;
148int main(
int argc,
char **)
150 std::cout <<
"OMPL version: " << OMPL_VERSION << std::endl;
152 std::filesystem::path path(TEST_RESOURCES_DIR);
153 Plane2DEnvironment env((path /
"ppm" /
"floor.ppm").
string().c_str(), argc == 1);
155 for (
unsigned int i = 0; i < 100; ++i)
ompl::base::State StateType
Define the type of state allocated by this space.
const T * as() const
Cast this instance to a desired type.
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
This namespace contains sampling based planning routines shared by both planning under geometric cons...
This namespace contains code that is specific to planning under geometric constraints.