44#include "boost/program_options.hpp"
45#include "../PlanarManipulator/PolyWorld.h"
46#include "../PlanarManipulator/PlanarManipulatorPolyWorld.h"
47#include "../PlanarManipulator/PlanarManipulator.h"
48#include "../PlanarManipulator/PlanarManipulatorStateSpace.h"
49#include "../PlanarManipulator/PlanarManipulatorStateValidityChecker.h"
50#include "../PlanarManipulator/PlanarManipulatorIKGoal.h"
51#include "MultiLevelPlanarManipulatorCommon.h"
53#include <ompl/geometric/planners/rrt/RRTConnect.h>
54#include <ompl/geometric/planners/rrt/RRT.h>
55#include <ompl/base/spaces/SE2StateSpace.h>
56#include <ompl/base/spaces/RealVectorStateSpace.h>
57#include <ompl/multilevel/planners/qrrt/QRRT.h>
58#include <ompl/multilevel/planners/qmp/QMP.h>
60#include <ompl/multilevel/datastructures/Projection.h>
61#include <ompl/multilevel/datastructures/projections/SE2_R2.h>
77 : Projection(bundle,
base), manip_(manip)
82 void project(
const State *xBundle, State *xBase)
const
84 std::vector<double> reals;
85 getBundle()->copyToReals(reals, xBundle);
87 Eigen::Affine2d eeFrame;
88 manip_->FK(reals, eeFrame);
90 double x = eeFrame.translation()(0);
91 double y = eeFrame.translation()(1);
92 double yaw = acos(eeFrame.matrix()(0, 0));
94 xBase->
as<SE2StateSpace::StateType>()->setXY(x, y);
95 xBase->
as<SE2StateSpace::StateType>()->setYaw(yaw);
97 getBundle()->printState(xBundle);
98 getBase()->printState(xBase);
101 void lift(
const State *xBase, State *xBundle)
const
103 std::vector<double> reals;
104 getBase()->copyToReals(reals, xBase);
107 Eigen::Affine2d eeFrame = Eigen::Affine2d::Identity();
108 eeFrame.translation()(0) = reals.at(0);
109 eeFrame.translation()(1) = reals.at(1);
110 eeFrame.rotate(reals.at(2));
112 std::vector<double> solution;
113 manip_->FABRIK(solution, eeFrame);
116 for (uint k = 0; k < solution.size(); k++)
118 angles[k] = solution.at(k);
123 PlanarManipulator *manip_;
128 Eigen::Affine2d baseFrame;
129 Eigen::Affine2d goalFrame;
132 PolyWorld world = createCorridorProblem(numLinks, baseFrame, goalFrame);
139 bounds.setLow(-M_PI);
140 bounds.setHigh(M_PI);
142 manipulator.setBounds(bounds.low, bounds.high);
145 si->setStateValidityChecker(std::make_shared<PlanarManipulatorCollisionChecker>(si, manipulator, &world));
146 si->setStateValidityCheckingResolution(0.001);
153 boundsWorkspace.setLow(-2);
154 boundsWorkspace.setHigh(+2);
158 siSE2->setStateValidityChecker(std::make_shared<SE2CollisionChecker>(siSE2, &world));
159 siSE2->setStateValidityCheckingResolution(0.001);
178 ompl::multilevel::ProjectionPtr projAB = std::make_shared<ProjectionJointSpaceToSE2>(space, spaceSE2, &manipulator);
188 std::vector<SpaceInformationPtr> siVec;
189 std::vector<ompl::multilevel::ProjectionPtr> projVec;
193 siVec.push_back(siSE2);
194 projVec.push_back(projAB);
197 auto planner = std::make_shared<ompl::multilevel::QRRT>(siVec, projVec);
205 for (
int i = 0; i < numLinks; ++i)
207 start_angles[i] = 1e-1 * (pow(-1, i)) + i * 1e-3;
217 std::vector<double> goalJoints;
218 manipulator.IK(goalJoints, goalFrame);
221 goal_angles[0] = 0.346324;
222 goal_angles[1] = 0.0828153;
223 goal_angles[2] = 2.96842;
224 goal_angles[3] = -2.17559;
225 goal_angles[4] = -0.718962;
226 goal_angles[5] = 0.16532;
227 goal_angles[6] = -0.228314;
228 goal_angles[7] = 0.172762;
231 pdef->addStartState(start);
232 pdef->setGoalState(goal, 1e-3);
234 si->freeState(start);
240 planner->setProblemDefinition(pdef);
248 PathPtr path = pdef->getSolutionPath();
253 WriteVisualization(manipulator, &world, pgeo);
A shared pointer wrapper for ompl::base::Path.
A shared pointer wrapper for ompl::base::ProblemDefinition.
The lower and upper bounds for an Rn space.
The definition of a state in Rn.
A state space representing SE(2).
A shared pointer wrapper for ompl::base::StateSpace.
ompl::base::State StateType
Define the type of state allocated by this space.
Definition of an abstract state.
const T * as() const
Cast this instance to a desired type.
Definition of a geometric path.
std::size_t getStateCount() const
Get the number of states (way-points) that make up this path.
void interpolate(unsigned int count)
Insert a number of states in a path so that the path is made up of exactly count states....
#define OMPL_INFORM(fmt,...)
Log a formatted information 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.
This namespace contains datastructures and planners to exploit multilevel abstractions,...
@ PROJECTION_TASK_SPACE
X \rightarrow T (A mapping from state space X to a task space T).
Main namespace. Contains everything in this library.
A class to store the exit status of Planner::solve().
@ EXACT_SOLUTION
The planner found an exact solution.
@ APPROXIMATE_SOLUTION
The planner found an approximate solution.