37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_TSRRT_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_TSRRT_
40 #include "ompl/base/ProjectionEvaluator.h"
41 #include "ompl/geometric/planners/PlannerIncludes.h"
42 #include "ompl/datastructures/NearestNeighbors.h"
48 OMPL_CLASS_FORWARD(TaskSpaceConfig);
53 virtual ~TaskSpaceConfig()
57 virtual int getDimension()
const = 0;
59 virtual void project(
const base::State *state, Eigen::Ref<Eigen::VectorXd> ts_proj)
const = 0;
62 virtual void sample(Eigen::Ref<Eigen::VectorXd> ts_proj)
const = 0;
66 virtual bool lift(
const Eigen::Ref<Eigen::VectorXd> &ts_proj,
const base::State *seed,
67 base::State *state)
const = 0;
87 class TSRRT :
public base::Planner
91 TSRRT(
const base::SpaceInformationPtr &si,
const TaskSpaceConfigPtr &task_space);
97 virtual base::PlannerStatus
solve(
const base::PlannerTerminationCondition &ptc);
138 template <
template <
typename T>
class NN>
141 nn_.reset(
new NN<Motion *>());
144 virtual void setup();
155 Motion(
const base::SpaceInformationPtr &si) :
state(si->allocState()),
parent(
nullptr)
168 Eigen::VectorXd proj;
177 double sqr_dist = 0.0;
178 for (
int ix = 0; ix < a->proj.size(); ++ix)
180 double sqr_val = (*b).proj[ix] - (*a).proj[ix];
189 std::shared_ptr<NearestNeighbors<Motion *>>
nn_;
205 TaskSpaceConfigPtr task_space_;
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
void setRange(double distance)
Set the range the planner is supposed to use.
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
void freeMemory()
Free the memory allocated by this planner.
Definition of an abstract state.
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
RNG rng_
The random number generator.
base::State * state
The state contained by the motion.
TSRRT(const base::SpaceInformationPtr &si, const TaskSpaceConfigPtr &task_space)
Constructor.
void setGoalBias(double goalBias)
Set the goal bias.
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
double maxDistance_
The maximum length of a motion to be added to a tree.
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)
Function that can solve the motion planning problem. This function can be called multiple times on th...
Motion * parent
The parent motion in the exploration tree.
virtual void getPlannerData(base::PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will upd...
double getGoalBias() const
Get the goal bias the planner is using.
double getRange() const
Get the range the planner is using.
Representation of a motion.
Main namespace. Contains everything in this library.