Class ProjectedStateSpace
Defined in File ProjectedStateSpace.h
Inheritance Relationships
Base Type
public ompl::base::ConstrainedStateSpace
(Class ConstrainedStateSpace)
Class Documentation
-
class ProjectedStateSpace : public ompl::base::ConstrainedStateSpace
ConstrainedStateSpace encapsulating a projection-based methodology for planning with constraints.
Z. Kingston, M. Moll, and L. E. Kavraki, “Sampling-Based Methods for Motion Planning with Constraints,” Annual Review of Control, Robotics, and Autonomous Systems, 2018. DOI: 10.1146/annurev-control-060117-105226 [PDF].
- Short Description
ProjectedStateSpace implements a projection-based methodology for constrained sampling-based planning, where points in ambient space are projected onto the constraint manifold via a projection operator, which in this case is implemented as a Newton’s method within the Constraint.
- External Documentation
For more information on constrained sampling-based planning using projection-based methods, see the following review paper. The section on projection-based methods cites most of the relevant literature.
Public Functions
-
inline ProjectedStateSpace(const StateSpacePtr &ambientSpace, const ConstraintPtr &constraint)
Construct an atlas with the specified dimensions.
-
~ProjectedStateSpace() override = default
Destructor.
-
inline virtual StateSamplerPtr allocDefaultStateSampler() const override
Allocate the default state sampler for this space.
-
inline virtual StateSamplerPtr allocStateSampler() const override
Allocate the previously set state sampler for this space.
-
virtual bool discreteGeodesic(const State *from, const State *to, bool interpolate = false, std::vector<State*> *geodesic = nullptr) const override
Traverse the manifold from from toward to. Returns true if we reached to, and false if we stopped early for any reason, such as a collision or traveling too far. No collision checking is performed if interpolate is true. If geodesic is not nullptr, the sequence of intermediates is saved to it, including a copy of from, as well as the final state, which is a copy of to if we reached to. Caller is responsible for freeing states returned in geodesic.