Class TangentBundleStateSpace
Defined in File TangentBundleStateSpace.h
Inheritance Relationships
Base Type
public ompl::base::AtlasStateSpace
(Class AtlasStateSpace)
Class Documentation
-
class TangentBundleStateSpace : public ompl::base::AtlasStateSpace
ConstrainedStateSpace encapsulating a planner-agnostic lazy atlas algorithm for planning on a constraint manifold.
B. Kim, T. T. Um, C. Suh, and F. C. Park, “Tangent bundle RRT: A randomized algorithm for constrained motion
planning,” Robotica 34.1 (2016): 202-225. DOI:
10.1017/S0263574714001234.- Short Description
TangentBundleStateSpace implements a lazy atlas-based methodology for constrained sampling-based planning, where the underlying constraint manifold is locally parameterized by charts (AtlasChart). The underlying constraint manifold can then be sampled and explored using the collection of these charts (an atlas). The difference between TangentBundleStateSpace and AtlasStateSpace is three-fold: TangentBundleStateSpace takes a lazy approach to evaluating the constraint function when traversing the manifold, TangentBundleStateSpace uses biased sampling for selected charts by default, and TangentBundleStateSpace does not use halfspace separation of charts.
- External Documentation
This state space is inspired by the work on Tangent Bundle RRT.
For more information on constrained sampling-based planning using atlas-based methods, see the following review paper. The section on atlas-based methods cites most of the relevant literature.
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].
Public Functions
-
TangentBundleStateSpace(const StateSpacePtr &ambientSpace, const ConstraintPtr &constraint)
-
virtual void sanityChecks() const override
Do sanity checks, minus geodesic constraint satisfiability (as this is a lazy method).
-
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.
-
virtual State *geodesicInterpolate(const std::vector<State*> &geodesic, double t) const override
Like interpolate(…), but interpolates between intermediate states already supplied in stateList from a previous call to discreteGeodesic(…, geodesic). The from and to states are the first and last elements stateList. Returns a pointer to a state in geodesic. As TangentBundleStateSpace employs a lazy approach to manifold traversal, additional fix-up is required to generate a state that satisfies constraints.