ConstrainedStateSpace.h
86 bool checkMotion(const State *s1, const State *s2, std::pair<State *, double> &lastValid) const override;
159 };
Constrained configuration space specific implementation of checkMotion() that uses discreteGeodesic()...
Definition: ConstrainedStateSpace.h:67
bool checkMotion(const State *s1, const State *s2) const override
Return whether we can step from s1 to s2 along the manifold without collision.
Definition: ConstrainedStateSpace.cpp:55
ConstrainedMotionValidator(SpaceInformation *si)
Constructor.
Definition: ConstrainedStateSpace.cpp:45
const ConstrainedStateSpace & ss_
Space in which we check motion.
Definition: ConstrainedStateSpace.h:90
A State in a ConstrainedStateSpace, represented as a dense real vector of values. For convenience and...
Definition: ConstrainedStateSpace.h:169
void copy(const Eigen::Ref< const Eigen::VectorXd > &other)
Copy the contents from a vector into this state. Uses the underlying copy operator used by Eigen for ...
Definition: ConstrainedStateSpace.h:181
StateType(const ConstrainedStateSpace *space)
Constructor. Requires space to setup information about underlying state.
Definition: ConstrainedStateSpace.h:172
A StateSpace that has a Constraint imposed upon it. Underlying space functions are passed to the ambi...
Definition: ConstrainedStateSpace.h:134
virtual State * geodesicInterpolate(const std::vector< State * > &geodesic, double t) const
Like interpolate(...), but interpolates between intermediate states already supplied in stateList fro...
Definition: ConstrainedStateSpace.cpp:287
void setLambda(double lambda)
Set lambda, where lambda * distance(x, y) is the maximum length of the geodesic x to y....
Definition: ConstrainedStateSpace.h:275
double getDelta() const
Get delta, the step size across the manifold.
Definition: ConstrainedStateSpace.h:284
void setSpaceInformation(SpaceInformation *si)
Sets the space information for this state space. Required for collision checking in manifold traversa...
Definition: ConstrainedStateSpace.cpp:198
const ConstraintPtr getConstraint() const
Returns the constraint that defines the underlying manifold.
Definition: ConstrainedStateSpace.h:308
virtual void clear()
Clear any allocated memory from the state space.
Definition: ConstrainedStateSpace.cpp:261
double lambda_
Manifold traversal from x to y is stopped if accumulated distance is greater than d(x,...
Definition: ConstrainedStateSpace.h:336
State * allocState() const override
Allocate a new state in this space.
Definition: ConstrainedStateSpace.cpp:265
void interpolate(const State *from, const State *to, double t, State *state) const override
Find a state between from and to around time t, where t = 0 is from, and t = 1 is the final state rea...
Definition: ConstrainedStateSpace.cpp:270
virtual bool discreteGeodesic(const State *from, const State *to, bool interpolate=false, std::vector< State * > *geodesic=nullptr) const =0
Traverse the manifold from from toward to. Returns true if we reached to, and false if we stopped ear...
double delta_
Step size when traversing the manifold and collision checking.
Definition: ConstrainedStateSpace.h:330
void constrainedSanityChecks(unsigned int flags) const
Do some sanity checks relating to discrete geodesic computation and constraint satisfaction....
Definition: ConstrainedStateSpace.cpp:111
ConstrainedStateSpace(const StateSpacePtr &ambientSpace, const ConstraintPtr &constraint)
Construct a constrained space from an ambientSpace and a constraint.
Definition: ConstrainedStateSpace.cpp:102
unsigned int getAmbientDimension() const
Returns the dimension of the ambient space.
Definition: ConstrainedStateSpace.h:296
bool isMetricSpace() const override
Returns false as the implicit constrained configuration space defined by the constraint is not metric...
Definition: ConstrainedStateSpace.h:199
unsigned int validSegmentCount(const State *s1, const State *s2) const override
Return the valid segment count on the manifold, as valid segment count is determined by delta_ and la...
Definition: ConstrainedStateSpace.h:226
SanityChecks
Flags used in a bit mask for constrained state space sanity checks, constraintSanityChecks().
Definition: ConstrainedStateSpace.h:139
@ CONSTRAINED_STATESPACE_GEODESIC_SATISFY
Check whether discrete geodesics satisfy the constraint at all points.
Definition: ConstrainedStateSpace.h:146
@ CONSTRAINED_STATESPACE_SAMPLERS
Check whether state samplers return constraint satisfying samples.
Definition: ConstrainedStateSpace.h:142
@ CONSTRAINED_STATESPACE_GEODESIC_CONTINUITY
Check whether discrete geodesics keep lambda_ * delta_ continuity.
Definition: ConstrainedStateSpace.h:150
@ CONSTRAINED_STATESPACE_JACOBIAN
Check if the constraint's numerical Jacobian approximates its provided Jacobian.
Definition: ConstrainedStateSpace.h:158
@ CONSTRAINED_STATESPACE_GEODESIC_INTERPOLATE
Check whether geodesicInterpolate(...) returns constraint satisfying states.
Definition: ConstrainedStateSpace.h:154
void sanityChecks() const override
Perform both constrained and regular sanity checks.
Definition: ConstrainedStateSpace.cpp:186
void setDelta(double delta)
Set delta, the step size for traversing the manifold and collision checking. Default defined by ompl:...
Definition: ConstrainedStateSpace.cpp:211
SpaceInformation * si_
SpaceInformation associated with this space. Required for early collision checking in manifold traver...
Definition: ConstrainedStateSpace.h:318
const ConstraintPtr constraint_
Constraint function that defines the manifold.
Definition: ConstrainedStateSpace.h:321
unsigned int getManifoldDimension() const
Returns the dimension of the manifold.
Definition: ConstrainedStateSpace.h:302
A shared pointer wrapper for ompl::base::Constraint.
Abstract definition for a class checking the validity of motions – path segments between states....
Definition: MotionValidator.h:65
A shared pointer wrapper for ompl::base::SpaceInformation.
The base class for space information. This contains all the information about the space planning is d...
Definition: SpaceInformation.h:82
A shared pointer wrapper for ompl::base::StateSpace.
Wrapper state type. Contains a reference to an underlying state.
Definition: WrapperStateSpace.h:104
State space wrapper that transparently passes state space operations through to the underlying space....
Definition: WrapperStateSpace.h:100
double * getValueAddressAtIndex(State *state, unsigned int index) const override
Many states contain a number of double values. This function provides a means to get the memory addre...
Definition: WrapperStateSpace.h:322
unsigned int getDimension() const override
Get the dimension of the space (not the dimension of the surrounding ambient space)
Definition: WrapperStateSpace.h:244
double distance(const State *state1, const State *state2) const override
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
Definition: WrapperStateSpace.h:274
Main namespace. Contains everything in this library.
Definition: ConstrainedSpaceInformation.h:53