Loading...
Searching...
No Matches
ConstrainedPlanningCommon.h
167 auto planner_msg = "List of which motion planner to use (multiple if benchmarking, one if planning). Choose from:\n"
174 desc.add_options()("planner,p", po::value<std::vector<enum PLANNER_TYPE>>(planners)->multitoken(), planner_msg);
194 auto range_msg = "Planner `range` value for planners that support this parameter. Automatically determined "
197 desc.add_options()("delta,d", po::value<double>(&options->delta)->default_value(om::CONSTRAINED_STATE_SPACE_DELTA),
199 desc.add_options()("lambda", po::value<double>(&options->lambda)->default_value(om::CONSTRAINED_STATE_SPACE_LAMBDA),
206 "tries", po::value<unsigned int>(&options->tries)->default_value(om::CONSTRAINT_PROJECTION_MAX_ITERATIONS),
228 auto alpha_msg = "Maximum angle between an atlas chart and the manifold. Must be in [0, PI/2].";
235 desc.add_options()("epsilon", po::value<double>(&options->epsilon)->default_value(om::ATLAS_STATE_SPACE_EPSILON),
244 desc.add_options()("alpha", po::value<double>(&options->alpha)->default_value(om::ATLAS_STATE_SPACE_ALPHA),
247 desc.add_options()("no-separate", po::bool_switch(&options->separate)->default_value(false), separate_msg);
250 po::value<unsigned int>(&options->charts)->default_value(om::ATLAS_STATE_SPACE_MAX_CHARTS_PER_EXTENSION),
257 ConstrainedProblem(enum SPACE_TYPE type, ob::StateSpacePtr space_, ob::ConstraintPtr constraint_)
521 bench->addExperimentParameter("n", "INTEGER", std::to_string(constraint->getAmbientDimension()));
522 bench->addExperimentParameter("k", "INTEGER", std::to_string(constraint->getManifoldDimension()));
523 bench->addExperimentParameter("n - k", "INTEGER", std::to_string(constraint->getCoDimension()));
535 planner->getSpaceInformation()->getStateSpace()->as<ompl::base::ConstrainedStateSpace>()->clear();
547 (boost::format("%1%_%2%_%3%_benchmark.log") % now % bench->getExperimentName() % spaceStr[type]).str();
Tangent space and bounding polytope approximating some patch of the manifold.
Definition AtlasChart.h:53
ConstrainedStateSpace encapsulating a planner-agnostic atlas algorithm for planning on a constraint m...
Definition AtlasStateSpace.h:128
void setExploration(double exploration)
Set the exploration parameter, which tunes the balance of refinement (sampling within known regions) ...
Definition AtlasStateSpace.h:234
A StateSpace that has a Constraint imposed upon it. Underlying space functions are passed to the ambi...
Definition ConstrainedStateSpace.h:134
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition PlannerData.h:175
void printGraphML(std::ostream &out=std::cout) const
Writes a GraphML file of this structure to the given stream.
Definition PlannerData.cpp:284
virtual void benchmark(const Request &req)
Benchmark the added planners on the defined problem. Repeated calls clear previously gathered data.
Definition Benchmark.cpp:353
void setPreRunEvent(const PreSetupEvent &event)
Set the event to be called before the run of a planner.
Definition Benchmark.h:276
const std::string & getExperimentName() const
Get the name of the experiment.
Definition Benchmark.h:242
bool saveResultsToFile(const char *filename) const
Save the results of the benchmark to a file.
Definition Benchmark.cpp:199
void addExperimentParameter(const std::string &name, const std::string &type, const std::string &value)
Add an optional parameter's information to the benchmark output. Useful for aggregating results over ...
Definition Benchmark.h:218
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition ConstrainedSpaceInformation.h:55
This namespace contains code that is specific to planning under geometric constraints.
Definition GeneticSearch.h:48
This namespace includes magic constants used in various places in OMPL.
Definition Constraint.h:52
static const double CONSTRAINT_PROJECTION_TOLERANCE
Default projection tolerance of a constraint unless otherwise specified.
Definition Constraint.h:55
static const unsigned int CONSTRAINT_PROJECTION_MAX_ITERATIONS
Maximum number of iterations in projection routine until giving up.
Definition Constraint.h:59
std::string as_string(const point &p)
Return string representation of point in time.
Definition Time.h:78
Includes various tools such as self config, benchmarking, etc.
Definition LightningRetrieveRepair.h:48
Definition ConstrainedPlanningCommon.h:212
A class to store the exit status of Planner::solve()
Definition PlannerStatus.h:49