RobWorkProject
23.9.11-
|
Path-planning for devices. More...
Classes | |
class | PlannerConstraint |
A tuple of (QConstraintPtr, QEdgeConstraintPtr). More... | |
class | PlannerUtil |
PlannerUtil provides various utilities useful in path planning. More... | |
class | QConstraint |
Interface for the checking for collisions for work cell states. More... | |
class | QIKSampler |
Interface for the sampling a configuration that solves an IK problem. More... | |
class | QNormalizer |
Normalization of configurations. More... | |
class | QSampler |
Interface for the sampling a configuration. More... | |
class | StateConstraint |
Interface for the checking for collisions for work cell states. More... | |
class | StopCriteria |
StopCriteria is a class for specifying an instant a compution should be aborted. More... | |
class | ARWExpand |
ARWExpand expands a random walk in the configuration space by one step. More... | |
class | SBLExpand |
Interface for sampling a configuration in the vicinity of some other configuration. More... | |
Typedefs | |
typedef rw::core::Ptr< PlannerConstraint > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< const PlannerConstraint > | CPtr |
smart pointer type to this const class | |
typedef rw::core::Ptr< QConstraint > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< const QConstraint > | CPtr |
smart pointer type to this const class | |
typedef rw::core::Ptr< QIKSampler > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< const QIKSampler > | CPtr |
smart pointer type to this const class | |
typedef rw::core::Ptr< QNormalizer > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< QSampler > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< const QSampler > | CPtr |
smart pointer type to this const class | |
typedef rw::core::Ptr< StateConstraint > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< const StateConstraint > | CPtr |
smart pointer type to this class | |
typedef rw::core::Ptr< StopCriteria > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< ARWExpand > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< SBLExpand > | Ptr |
Smart pointer type for SBLExpand. | |
typedef std::pair< rw::math::Q, rw::math::Q > | QBox |
A configuration space in the shape of a box. More... | |
Enumerations | |
enum | EstimateType { WORSTCASE = 0 , AVERAGE } |
Description of the different estimation type possible in the estimateMotionWeights(EsitmateType, size_t) method. More... | |
Functions | |
PlannerConstraint () | |
Default constructed without constraints initialized. | |
PlannerConstraint (rw::core::Ptr< rw::pathplanning::QConstraint > constraint, QEdgeConstraint::Ptr edge) | |
A (QConstraintPtr, QEdgeConstraintPtr) tuple. More... | |
bool | inCollision (const rw::math::Q &q) |
Forwards call to the QConstraint wrapped by the PlannerConstraint. | |
bool | inCollision (const rw::math::Q &q1, const rw::math::Q &q2) |
Forwards call to the QEdgeConstraint wrapped by the PlannerConstraint. | |
QConstraint & | getQConstraint () const |
The configuration constraint. | |
QEdgeConstraint & | getQEdgeConstraint () const |
The edge constraint. | |
const rw::core::Ptr< rw::pathplanning::QConstraint > & | getQConstraintPtr () const |
The configuration constraint pointer. | |
const QEdgeConstraint::Ptr & | getQEdgeConstraintPtr () const |
The edge constraint pointer. | |
static PlannerConstraint | make (rw::core::Ptr< rw::pathplanning::QConstraint > constraint, QEdgeConstraint::Ptr edge) |
A (QConstraintPtr, QEdgeConstraintPtr) tuple. More... | |
static PlannerConstraint | make (rw::core::Ptr< rw::proximity::CollisionDetector > detector, rw::core::Ptr< const rw::models::Device > device, const rw::kinematics::State &state) |
Planner constraint for a collision detector. More... | |
static PlannerConstraint | make (rw::core::Ptr< rw::proximity::CollisionStrategy > strategy, rw::core::Ptr< rw::models::WorkCell > workcell, rw::core::Ptr< const rw::models::Device > device, const rw::kinematics::State &state) |
Planner constraint for a collision strategy. More... | |
static PlannerConstraint | make (rw::core::Ptr< rw::proximity::CollisionStrategy > strategy, const rw::proximity::CollisionSetup &setup, rw::core::Ptr< rw::models::WorkCell > workcell, rw::core::Ptr< const rw::models::Device > device, const rw::kinematics::State &state) |
Planner constraint for a collision strategy and collision setup. More... | |
static bool | inCollision (const PlannerConstraint &constraint, const std::vector< rw::math::Q > &path) |
Collision checking for a path of configurations. More... | |
static bool | inCollision (const PlannerConstraint &constraint, const rw::math::Q &start, const rw::math::Q &end, bool checkStart=true, bool checkEnd=true) |
Collision checking for a segment. More... | |
static bool | inCollision (const PlannerConstraint &constraint, const rw::math::Q &q) |
Collision checking for a configuration. More... | |
static rw::math::QMetric::Ptr | normalizingInfinityMetric (const rw::models::Device::QBox &bounds, double length=1) |
Weighted infinity metric that maps the maps the longest vector in the configuration space to a given length. More... | |
static rw::math::QMetric::Ptr | timeMetric (const rw::models::Device &device) |
Metric for the distance in time between a pair of configurations. More... | |
static rw::math::QMetric::Ptr | timeMetric (const rw::math::Q &speed) |
Metric for the distance in time between a pair of configurations. More... | |
static rw::math::Q | estimateMotionWeights (const rw::models::Device &device, rw::core::Ptr< const rw::kinematics::Frame > frame, const rw::kinematics::State &initialState, EstimateType type, size_t samples) |
Estimate the distance traveled by the frame, when moving the joints. More... | |
static rw::math::Q | clampPosition (const rw::models::Device &device, const rw::math::Q &q) |
Clamps values to be within bounds. More... | |
static rw::math::Q | clampPosition (const rw::models::Device::QBox &bounds, const rw::math::Q &q) |
Clamps values to be within bounds. More... | |
virtual | ~QConstraint () |
Destructor. | |
virtual void | setLog (rw::core::Log::Ptr log) |
Set the log to be used for writing debug info. More... | |
void | update (const rw::kinematics::State &state) |
Updates the constraint with a new state. More... | |
bool | inCollision (const rw::math::Q &q) const |
True if the work cell is considered to be in collision for the device configuration q. | |
static QConstraint::Ptr | makeFixed (bool value) |
A fixed constraint. The fixed constraint always returns value from inCollision(). | |
static QConstraint::Ptr | makeBounds (const rw::models::Device::QBox &bounds) |
Constraint for the bounds of the configuration space. The configuration is considered to be in collision if it is outside of the bounds given by bounds. | |
static QConstraint::Ptr | make (rw::core::Ptr< StateConstraint > detector, rw::models::Device::CPtr device, const rw::kinematics::State &state) |
Map a state constraint to a configuration constraint. | |
static QConstraint::Ptr | make (rw::core::Ptr< rw::proximity::CollisionDetector > detector, rw::models::Device::CPtr device, const rw::kinematics::State &state) |
Map a collision detector to a configuration constraint. | |
static QConstraint::Ptr | makeMerged (const std::vector< QConstraint::Ptr > &constraints) |
Combine a set of configuration constraints into a single configuration constraint. | |
static QConstraint::Ptr | makeMerged (const QConstraint::Ptr &ca, const QConstraint::Ptr &cb) |
Combine a pair of configuration constraints into a single configuration constraint. | |
static QConstraint::Ptr | makeNormalized (const QConstraint::Ptr &constraint, const std::pair< rw::math::Q, rw::math::Q > &bounds) |
Map a configuration constraint for standard configurations into a configuration constraint for normalized configurations. More... | |
static QConstraint::Ptr | makeNormalized (const QConstraint::Ptr &constraint, const rw::models::Device &device) |
Map a configuration constraint for standard configurations into a configuration constraint for normalized configurations. More... | |
static QConstraint::Ptr | makeNormalized (const QConstraint::Ptr &constraint, const QNormalizer &normalizer) |
Map a configuration constraint for standard configurations into a configuration constraint for normalized configurations. More... | |
virtual bool | doInCollision (const rw::math::Q &q) const =0 |
Subclass implementation of the inCollision() method. | |
virtual void | doSetLog (rw::core::Log::Ptr log)=0 |
Set a log. More... | |
virtual void | doUpdate (const rw::kinematics::State &state) |
Update constraint. More... | |
QConstraint () | |
rw::math::Q | sample (const rw::math::Transform3D<> &target) |
Sample a configuration that solves an IK problem for target. More... | |
bool | empty () const |
True if the sampler is known to contain no more configurations. | |
virtual | ~QIKSampler () |
Destructor. | |
static QIKSampler::Ptr | make (rw::core::Ptr< rw::models::Device > device, const rw::kinematics::State &state, rw::core::Ptr< rw::invkin::IterativeIK > solver=NULL, rw::core::Ptr< QSampler > seed=NULL, int maxAttempts=-1) |
An IK sampler based on an iterative IK solver. More... | |
static QIKSampler::Ptr | makeConstrained (QIKSampler::Ptr sampler, rw::core::Ptr< QConstraint > constraint, int maxAttempts=-1) |
An IK sampler filtered by a constraint. More... | |
QIKSampler () | |
Constructor. | |
virtual rw::math::Q | doSample (const rw::math::Transform3D<> &target)=0 |
Subclass implementation of the sample() method. | |
virtual bool | doEmpty () const |
Subclass implementation of the empty() method. More... | |
rw::math::Q | fromNormalized (const rw::math::Q &q) const |
Convert from a normalized configuration to a real configuration. | |
rw::math::Q | toNormalized (const rw::math::Q &q) const |
Convert a real configuration to a normalized configuration. | |
void | setFromNormalized (rw::math::Q &q) const |
Convert from a normalized configuration to a real configuration and assign the real configuration to q. | |
void | setToNormalized (rw::math::Q &q) const |
Convert a real configuration to a normalized configuration and write the normalized configuration to q. | |
const std::pair< rw::math::Q, rw::math::Q > & | getBounds () const |
The box of the configuration space with respect to which normalization is done. | |
QNormalizer (const std::pair< rw::math::Q, rw::math::Q > &bounds) | |
Normalizer for the configuration space box given by bounds. | |
static QNormalizer | identity () |
Normalizer for the already normalized configuration space box. | |
rw::math::Q | sample () |
Sample a configuration. More... | |
bool | empty () const |
True if the sampler is known to contain no more configurations. | |
virtual | ~QSampler () |
Destructor. | |
static QSampler::Ptr | makeEmpty () |
Empty sampler. | |
static QSampler::Ptr | makeFixed (const rw::math::Q &q) |
Sampler that always returns the same configuration. More... | |
static QSampler::Ptr | makeSingle (const rw::math::Q &q) |
Sampler that always returns a single configuration. More... | |
static QSampler::Ptr | makeFinite (const std::vector< rw::math::Q > &qs) |
Sampler for the values of a finite sequence. More... | |
static QSampler::Ptr | makeFinite (QSampler::Ptr sampler, int cnt) |
A sampler to that returns only the first cnt samples from another sampler. More... | |
static QSampler::Ptr | makeUniform (const rw::models::Device::QBox &bounds) |
Uniform random sampling for a box of the configuration space. | |
static QSampler::Ptr | makeUniform (const rw::models::Device &device) |
Uniform random sampling for a device. | |
static QSampler::Ptr | makeUniform (rw::models::Device::CPtr device) |
Uniform random sampling for a device. | |
static QSampler::Ptr | makeNormalized (QSampler::Ptr sampler, const QNormalizer &normalizer) |
Map a sampler of standard configurations into a sampler of normalized configurations. | |
static QSampler::Ptr | make (rw::core::Ptr< QIKSampler > sampler, const rw::math::Transform3D<> &target) |
A sampler of IK solutions for a specific target. More... | |
static QSampler::Ptr | makeConstrained (QSampler::Ptr sampler, rw::core::Ptr< const QConstraint > constraint, int maxAttempts=-1) |
A sampler filtered by a constraint. More... | |
static QSampler::Ptr | makeBoxDirectionSampler (const rw::models::Device::QBox &bounds) |
Sampler of direction vectors for a box shaped configuration space. More... | |
QSampler () | |
Constructor. | |
virtual rw::math::Q | doSample ()=0 |
Subclass implementation of the sample() method. | |
virtual bool | doEmpty () const |
Subclass implementation of the empty() method. More... | |
virtual void | setLog (rw::core::Ptr< rw::core::Log > log) |
Set the log to be used for writing debug info. More... | |
bool | inCollision (const rw::kinematics::State &state) const |
True if the work cell is considered to be in collision for the work cell state state. | |
virtual | ~StateConstraint () |
static StateConstraint::Ptr | make (rw::core::Ptr< rw::proximity::CollisionDetector > detector) |
Map a collision detector to a state constraint. | |
static StateConstraint::Ptr | make (const std::vector< StateConstraint::Ptr > &constraints) |
Combine a set of state constraints into a single state constraint. | |
virtual bool | doInCollision (const rw::kinematics::State &state) const =0 |
Subclass implementation of the inCollision() method. | |
virtual void | doSetLog (rw::core::Ptr< rw::core::Log > log)=0 |
Set a log. More... | |
StateConstraint () | |
Constructor. | |
bool | stop () const |
True is returned when the computation should be stopped. | |
StopCriteria::Ptr | instance () const |
A new instance of the property constructed to match the original initial state of the criteria. More... | |
virtual | ~StopCriteria () |
Destructor. | |
static StopCriteria::Ptr | stopAfter (double time) |
Stop the computation after time seconds from now. More... | |
static StopCriteria::Ptr | stopNever () |
Never stop the computation. | |
static StopCriteria::Ptr | stopNow () |
Immediately stop the computation. | |
static StopCriteria::Ptr | stopByFlag (bool *stop) |
Stop the computation when stop says so. More... | |
static StopCriteria::Ptr | stopByFun (boost::function< bool()> fun) |
Stop the computation when fun says so. | |
static StopCriteria::Ptr | stopCnt (int cnt) |
Stop the computation after cnt calls of the stop criteria. | |
static StopCriteria::Ptr | stopEither (const std::vector< StopCriteria::Ptr > &criteria) |
Stop if either of criteria says stop. | |
static StopCriteria::Ptr | stopEither (const StopCriteria::Ptr &a, const StopCriteria::Ptr &b) |
Stop if either a or b says stop. | |
StopCriteria () | |
Constructor. | |
virtual bool | doStop () const =0 |
Subclass implementation of the stop() method. | |
virtual StopCriteria::Ptr | doInstance () const =0 |
Subclass implementation of the instance() method. | |
bool | expand () |
Expand the path by one step and return true if a new configuration was added to the path. More... | |
ARWExpand::Ptr | duplicate (const rw::math::Q &start) const |
Construct a new random walk with start node at start. | |
virtual | ~ARWExpand () |
Destructor. | |
const rw::trajectory::QPath & | getPath () const |
The current path of the random walk. | |
static ARWExpand::Ptr | make (const rw::models::Device::QBox &bounds, const rw::pathplanning::PlannerConstraint &constraint, const rw::math::Q &minVariances=rw::math::Q(), int historySize=-1) |
Constructor. More... | |
ARWExpand () | |
Constructor. | |
virtual bool | doExpand ()=0 |
Subclass implementation of the expand() method. More... | |
virtual ARWExpand::Ptr | doDuplicate (const rw::math::Q &start) const =0 |
Subclass implementation of the duplicate() method. | |
rw::math::Q | expand (const rw::math::Q &q) |
A configuration sampled from the vicinity of q. More... | |
static SBLExpand::Ptr | makeUniformBox (const QBox &outer, const QBox &inner) |
static SBLExpand::Ptr | makeUniformBox (const QBox &outer, double ratio) |
static SBLExpand::Ptr | makeShrinkingUniformBox (rw::core::Ptr< rw::pathplanning::QConstraint > constraint, const QBox &outer, const QBox &inner) |
Sample within a box of decreasing size until a collision free configuration is found. More... | |
static SBLExpand::Ptr | makeShrinkingUniformBox (rw::core::Ptr< rw::pathplanning::QConstraint > constraint, const QBox &outer, double ratio) |
Sample within a box of shrinking size until a collision free configuration is found. More... | |
static SBLExpand::Ptr | makeShrinkingUniformJacobianBox (rw::core::Ptr< rw::pathplanning::QConstraint > constraint, rw::core::Ptr< rw::models::Device > device, const rw::kinematics::State &state, rw::core::Ptr< rw::models::JacobianCalculator > jacobian, double angle_max=-1, double disp_max=-1) |
Sample within a box of shrinking size until a collision free configuration is found. More... | |
virtual | ~SBLExpand () |
Destructor. | |
SBLExpand () | |
Constructor. | |
virtual rw::math::Q | doExpand (const rw::math::Q &q)=0 |
Subclass implementation of the expand() method. | |
Variables | |
rw::trajectory::QPath | _path |
The path of random walk. | |
Path-planning for devices.
typedef std::pair<rw::math::Q, rw::math::Q> QBox |
A configuration space in the shape of a box.
The box is given by a lower and upper corner.
enum EstimateType |
|
static |
Clamps values to be within bounds.
The method treats all joints individually and clamps them to be within the position bounds of the device
device | [in] The device for the configurations. |
q | [in] Configuration to clamp |
|
static |
Clamps values to be within bounds.
The method treats all joints individually and clamps them to be within the position bounds of the configuration space box.
bounds | [in] The bounds of the configuration space |
q | [in] Configuration to clamp |
|
protectedvirtual |
Subclass implementation of the empty() method.
By default the sampler is assumed to be sampling an infinite set of configurations. IOW. the function returns false by default.
|
protectedvirtual |
Subclass implementation of the empty() method.
By default the sampler is assumed to be sampling an infinite set of configurations. IOW. the function returns false by default.
|
protectedpure virtual |
Subclass implementation of the expand() method.
The doExpand() adds one or more nodes to _path if and only if the method returns true.
|
protectedpure virtual |
Set a log.
log | [in] the log. |
|
protectedpure virtual |
Set a log.
log | [in] the log. |
|
inlineprotectedvirtual |
Update constraint.
state | [in] the state. |
|
static |
Estimate the distance traveled by the frame, when moving the joints.
The estimate is based on sampling samples random configuration and using the Jacobian to estimate the distance traveled when moving the joints. This estimate can be used in the WeightedEuclideanMetric.
device | [in] Device to estimate weights for |
frame | [in] Frame to calculate weights for. If null the device end frame will be used |
initialState | [in] Initial state to use in estimation |
type | [in] The estimation type |
samples | [in] The number of samples to use (default 1000) |
bool expand | ( | ) |
Expand the path by one step and return true if a new configuration was added to the path.
The current path can be retrieved with ARWExpand::getPath().
|
inline |
A configuration sampled from the vicinity of q.
Implementation dependant, the sampler may return the empty configuration if no configurations can be sampled near q.
|
inlinestatic |
Collision checking for a configuration.
constraint | [in] Collision checking constraint. |
q | [in] Configuration to check for collisions. |
|
static |
Collision checking for a segment.
start | [in] Start of segment |
end | [in] End of segment |
constraint | [in] Constraint for segment |
checkStart | [in] Check start configuration for collision. |
checkEnd | [in] Check end configuration for collision. |
|
static |
Collision checking for a path of configurations.
Each configuration and edge of path is checked using the configuration and edge constraints of constraint.
constraint [in] Constraint for path.
path [in] Sequence of configurations.
StopCriteria::Ptr instance | ( | ) | const |
A new instance of the property constructed to match the original initial state of the criteria.
This implies, for example, that instance() called for a time criteria creates a new criteria that stops after the same amount of time that was specified for the original stop criteria.
Not all stop criteria returned are required to behave this way. For some types of stop criteria, the instances of the stop criteria will be effectively identical to the stop criteria itself.
|
static |
Constructor.
The expansion method computes the variance for the latest historySize elements of the path and performs one step sampled from a Gaussian distribution with the computed variances. Variances lower than minVariances are never used.
If minVariances is empty, then a default value is chosen based on bounds.
If historySize is negative, a default value is chosen.
bounds | [in] Configuration space bounds. |
constraint | [in] Path planning constraint. |
minVariances | [in] Minimum variances. |
historySize | [in] Number of previous elements of the path to use for variance computation. |
|
static |
A sampler of IK solutions for a specific target.
sampler | [in] Sampler of IK solutions for target. |
target | [in] Target for IK solver. |
|
static |
An IK sampler based on an iterative IK solver.
All solutions returned are checked to be within the bounds of the device.
device | [in] The device for which seeds are sampled. |
state | [in] Fixed state with respect to which IK is solved. |
solver | [in] Optional IK solver for device and state. |
seed | [in] Optional sampler of seeds to feed the IK solver. |
maxAttempts | [in] Optional number of seeds to feed the IK solver. If maxAttempts is negative, a default value for maxAttempts is chosen. |
|
static |
A (QConstraintPtr, QEdgeConstraintPtr) tuple.
This is equivalent to the standard constructor.
|
static |
Planner constraint for a collision detector.
Path are checked discretely for a default device dependent resolution.
|
static |
Planner constraint for a collision strategy and collision setup.
Path are checked discretely for a default device dependent resolution.
|
static |
Planner constraint for a collision strategy.
Path are checked discretely for a default device dependent resolution.
The default collision setup of the workcell is used.
|
static |
Sampler of direction vectors for a box shaped configuration space.
Each random direction vector is found by sampling a configuration uniformly at random from bounds, and returning the vector from the center of the box to the configuration. The returned direction vector can therefore be of length zero.
|
static |
An IK sampler filtered by a constraint.
For each call of sample() up to maxAttempts configurations are extracted from sampler and checked by constraint. The first sample that satisfies the constraint is returned; if no such were found the empty configuration is returned.
If maxAttempts is negative, then sampler is sampled forever until either the sampler is empty or a configuration satisfying constraint is found.
|
static |
A sampler filtered by a constraint.
For each call of sample() up to maxAttempts configurations are extracted from sampler and checked by constraint. The first sample that satisfies the constraint is returned; if no such were found the empty configuration is returned.
If maxAttempts is negative (this is the default), then sampler is sampled forever until either the sampler is empty or a configuration satisfying constraint is found.
|
static |
|
static |
A sampler to that returns only the first cnt samples from another sampler.
The sampler is considered empty as soon as sampler is empty or the sampler has been called cnt times or more.
|
static |
Sampler that always returns the same configuration.
The sampler is considered never empty (empty() always returns false).
|
static |
Map a configuration constraint for standard configurations into a configuration constraint for normalized configurations.
Configuration values are mapped from normalized configurations into standard configurations using normalizer.
|
static |
Map a configuration constraint for standard configurations into a configuration constraint for normalized configurations.
Configuration values are mapped from the range [0, 1] into the corresponding position in the configuration space of device.
|
static |
Map a configuration constraint for standard configurations into a configuration constraint for normalized configurations.
Configuration values are mapped from the range [0, 1] into the corresponding position in the box bounds.
|
static |
Sample within a box of decreasing size until a collision free configuration is found.
The inner box shrinks in size as 1, 1/2, 1/3, ...
This form of expansion is typical for SBL planners.
The inner and outer box are specified as explained for makeUniformBox().
|
static |
Sample within a box of shrinking size until a collision free configuration is found.
The inner box shrinks in size as 1, 1/2, 1/3, ...
This form of expansion is typical for SBL planners.
The inner and outer box are specified as explained for makeUniformBox().
|
static |
Sample within a box of shrinking size until a collision free configuration is found.
The size of the inner box depends on the Jacobian of the current configuration. The radius for the i'th dimension of the inner box is
R_i = min(angle_max / angle_vel, disp_max / disp_vel)
where angle_vel is the magnitude of the angular velocity and disp_vel is the magnitude of the translational velocity.
If jacobian is NULL, a default device Jacobian is chosen based on device.
If angle_max or disp_max is negative, a default value for the variable is chosen.
The inner box shrinks in size as 1, 1/2, 1/3, ...
|
static |
|
static |
@brief Expansion within the overlap of an inner and outer box. Given a configuration \b q, the expand() method returns a configuration sampled uniformly at random from the intersection between
and
Given a \b device, you typically use \b device.getBounds() as the box for the outer configuration space. If the overlap between the boxes is empty, expand() returns the empty configuration.
|
static |
@brief Expansion within a scaled down box of the configuration space. Given a configuration \b q, the expand() method samples a configuration uniformly at random from the intersection between
and
where inner equals outer scaled by a factor of ratio and centered at origo.
This is a form of expansion you will use in a standard implementation of an SBL planner.
ratio must be positive.
If outer is non-empty, the expand() method will always return a non-empty configuration.
|
static |
Weighted infinity metric that maps the maps the longest vector in the configuration space to a given length.
bounds | [in] Lower and upper corner of the configuration space. |
length | [in] The wanted distance between lower and upper corner. |
PlannerConstraint | ( | rw::core::Ptr< rw::pathplanning::QConstraint > | constraint, |
QEdgeConstraint::Ptr | edge | ||
) |
A (QConstraintPtr, QEdgeConstraintPtr) tuple.
The constraints must be non-null.
|
inlineprotected |
Constructor
|
inline |
|
inline |
|
virtual |
Set the log to be used for writing debug info.
log | [in] Log to which debug information is to be written |
|
virtual |
Set the log to be used for writing debug info.
log | [in] Log to which debug information is to be written |
|
static |
Stop the computation after time seconds from now.
RobWork does not link with a thread library, and therefore this function is implemented by polling a timer. This makes the function relatively slow for its purpose.
|
static |
Stop the computation when stop says so.
stop must be non-null.
Ownership of stop is not taken.
|
static |
Metric for the distance in time between a pair of configurations.
The metric implements a simple scaled infinity-norm metric: The metric assumes that the joints move synchronously with the joint velocities given by speed.
|
static |
Metric for the distance in time between a pair of configurations.
The metric implements a simple scaled infinity-norm metric: The metric assumes that the joints move synchronously with the maximum joint velocities given by device.
void update | ( | const rw::kinematics::State & | state | ) |
Updates the constraint with a new state.
The method might not have an effect on all constrainttypes.
|
inlinevirtual |
Destructor