PlanarManipulatorDemo.cpp
79 Problem(int links, const std::string& problemName, PolyWorld &&world, const Eigen::Affine2d &baseFrame, const Eigen::Affine2d &goalFrame)
80 : name(problemName), manipulator(links, 1.0 / links), world(std::move(world)), goalFrame(goalFrame)
145 ompl::base::GoalPtr goal(new PlanarManipulatorIKGoal(setup->getSpaceInformation(), problem.goalFrame,
155 ompl::base::RealVectorBounds GetReachableWorkspaceBounds(Point origin, double chainLength, const Problem &problem)
186 const ompl::base::RealVectorBounds reachable_bounds = GetReachableWorkspaceBounds(origin, chainLength, problem);
188 ompl::geometric::TaskSpaceConfigPtr task_space_ptr(new PlanarManipTaskSpaceConfig(&manip, reachable_bounds));
196 ompl::geometric::XXLDecompositionPtr getXXLDecomp(const ompl::base::SpaceInformationPtr &si, const Problem &problem,
208 const ompl::base::RealVectorBounds reachable_bounds = GetReachableWorkspaceBounds(origin, chainLength, problem);
230 void postRunEvent(const ompl::base::PlannerPtr &planner, ompl::tools::Benchmark::RunProperties &run,
243 manip->FK(path.getState(i + 1)->as<PlanarManipulatorStateSpace::StateType>()->values, endFrames);
252 void BenchmarkProblem(ompl::geometric::SimpleSetupPtr setup, const Problem &problem, int runs, double timeout)
258 ompl::base::PlannerPtr tsrrt(new ompl::geometric::TSRRT(setup->getSpaceInformation(), getTaskSpaceConfig(problem)));
269 setup->getSpaceInformation(), getXXLDecomp(setup->getSpaceInformation(), problem, /*xySlices*/ 1)));
286 benchmark.setPostRunEvent([&](const ompl::base::PlannerPtr &planner, ompl::tools::Benchmark::RunProperties &run) {
289 benchmark.addExperimentParameter("num_links", "INTEGER", boost::lexical_cast<std::string>(numLinks));
290 benchmark.addExperimentParameter("cells", "INTEGER", boost::lexical_cast<std::string>(xySlices));
299 void WriteVisualization(const Problem &problem, const ompl::geometric::PathGeometric &path, int xySlices)
317 fout << numLinks << " " << linkLength << " " << basePose.translation()(0) << " " << basePose.translation()(1) << " "
330 void SolveProblem(ompl::geometric::SimpleSetupPtr setup, const Problem &problem, double timeout, bool write_viz_out)
A shared pointer wrapper for ompl::base::SpaceInformation.
A shared pointer wrapper for ompl::geometric::SimpleSetup.
Create the set of classes typically needed to solve a geometric problem.
Definition: SimpleSetup.h:126
Bi-directional Range-Limited Random Tree (Ryan Luna's Random Tree)
Definition: BiRLRT.h:127
Definition: PlanarManipulator.h:43
A shared pointer wrapper for ompl::base::Planner.
void setLogLevel(LogLevel level)
Set the minimum level of logging data to output. Messages with lower logging levels will not be recor...
Definition: Console.cpp:136
The definition of a state in Rn
Definition: RealVectorStateSpace.h:141
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:112
std::size_t getStateCount() const
Get the number of states (way-points) that make up this path.
Definition: PathGeometric.h:292
Bi-directional KPIECE with one level of discretization.
Definition: BKPIECE1.h:137
Definition: XXL.h:128
Definition: PolyWorld.h:80
A shared pointer wrapper for ompl::base::StateSpace.
Search Tree with Resolution Independent Density Estimation.
Definition: STRIDE.h:110
void interpolate(unsigned int count)
Insert a number of states in a path so that the path is made up of exactly count states....
Definition: PathGeometric.cpp:337
A shared pointer wrapper for ompl::base::Goal.
std::map< std::string, std::string > RunProperties
The data collected from a run of a planner is stored as key-value pairs.
Definition: Benchmark.h:175
Kinematic Planning by Interior-Exterior Cell Exploration.
Definition: KPIECE1.h:135
A shared pointer wrapper for ompl::geometric::XXLDecomposition.
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:111