sdurw_pathplanning module

class sdurw_pathplanning.sdurw_pathplanning.CartesianAnalysis

Bases: object

Result struct for Cartesian analysis

__init__()

Construct CartesianAnalysis struct with length initialized to 0

property distances

Total distance travelled in the x,y and z directions

property length

Cartesian length of the Path

property lower

Lower bound on the Cartesian position

property thisown

The membership flag

property upper

Upper bound on the Cartesian position

class sdurw_pathplanning.sdurw_pathplanning.ClearanceAnalysis

Bases: object

Result struct for CleracenAnalysis

__init__()

Construct ClearanceAnalysis struct with distances initialized to 0

property average

Average clearance

property min

Minimum clearance

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.JointSpaceAnalysis

Bases: object

Result struct for joint space analysis

__init__()

Constructs JointSpaceAnalysis struct initialized to zero.

property length

Total length in joint space

property nodecount

Number of nodes

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.PathAnalyzer(device, state)

Bases: object

The PathAnalyzer provides a set a basic tools for analyzing a path.

Features in the PathAnalyzer include analysis of joint space, Cartesian space, estimation of execution time and measures for clearance. See more details in the result structs PathAnalyzer::JointSpaceAnalysis, PathAnalyzer::CartesianAnalysis, PathAnalyzer::TimeAnalysis and PathAnalyzer::ClearanceAnalysis.

__init__(device, state)

Construct PathAnalyzer for a specific device

Parameters
  • device (rw::core::Ptr< rw::models::Device const >) – [in] Device to be associated with the path

  • state (State) – [in] State of the workcell

analyzeCartesian(path, frame)

Performs analysis in Cartesian space.

The method calculates the Cartesian distance travelled by the speficied frame. It provides the total distance travelled, the coordinate wise distances, and upper and lower bounds on the location of the frame during the path.

Parameters
  • path (rw::trajectory::QPath) – [in] Path to analyze

  • frame (rw::core::Ptr< rw::kinematics::Frame >) – [in] Frame for which to analyze the path.

Return type

CartesianAnalysis

Returns

Result of the analysis.

analyzeClearance(path, distanceCalculator)

Performs an analysis of the clearance

Calculates the average and minimum clearance along a path. Only the nodes of the path are sampled. The path should therefore be divided with the desired resolution before invoking this method.

Parameters
  • path (rw::trajectory::QPath) – [in] Path to analyze

  • distanceCalculator (rw::core::Ptr< rw::proximity::DistanceCalculator const >) – [in] DistanceCalculator to be used in the analysis

Return type

ClearanceAnalysis

Returns

Result of the analysis.

analyzeJointSpace(path, metric=0)

Performs joint space analysis of path.

Parameters
  • path (rw::trajectory::QPath) – [in] Path to analyze

  • metric (Ptr, optional) – [in] Metric to use for calculating the distance in joint space.

Return type

JointSpaceAnalysis

Returns

Result of the joint space analysis

analyzeTime(path)

Peforms analysis of the time

Calculates the time needed to execute the path when considering the dynamics.

Parameters

path (rw::trajectory::QPath) – [in] Path to analyze.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.PathPlannerQQ(*args, **kwargs)

Bases: object

Path planner interface.

PathPlanner<From, To, Path> plans a path in the configuration space

From from a start configuration of type From to a goal destination

specified by a parameter of type To. The path is of type Path.

__init__(*args, **kwargs)
getProperties(*args)

Overload 1:

Property map for the planner.


Overload 2:

Property map for the planner.

query(*args)

Overload 1:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (Q) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • stop (StopCriteria) – [in] Abort the planning when stop returns true.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 2:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (Q) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • time (float) – [in] Abort the planning after time seconds.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 3:

Plan a path from the configuration from to the destination to.

The planner runs until it gives up (which may be never).

Parameters
  • from (Q) – [in] start configuration for path.

  • to (Q) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.PathPlannerQQSampler(*args, **kwargs)

Bases: object

Path planner interface.

PathPlanner<From, To, Path> plans a path in the configuration space

From from a start configuration of type From to a goal destination

specified by a parameter of type To. The path is of type Path.

__init__(*args, **kwargs)
getProperties(*args)

Overload 1:

Property map for the planner.


Overload 2:

Property map for the planner.

query(*args)

Overload 1:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (QSampler) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • stop (StopCriteria) – [in] Abort the planning when stop returns true.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 2:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (QSampler) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • time (float) – [in] Abort the planning after time seconds.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 3:

Plan a path from the configuration from to the destination to.

The planner runs until it gives up (which may be never).

Parameters
  • from (Q) – [in] start configuration for path.

  • to (QSampler) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.PathPlannerQTransform3D(*args, **kwargs)

Bases: object

Path planner interface.

PathPlanner<From, To, Path> plans a path in the configuration space

From from a start configuration of type From to a goal destination

specified by a parameter of type To. The path is of type Path.

__init__(*args, **kwargs)
getProperties(*args)

Overload 1:

Property map for the planner.


Overload 2:

Property map for the planner.

query(*args)

Overload 1:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (rw::math::Transform3D< double >) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • stop (StopCriteria) – [in] Abort the planning when stop returns true.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 2:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (rw::math::Transform3D< double >) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • time (float) – [in] Abort the planning after time seconds.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 3:

Plan a path from the configuration from to the destination to.

The planner runs until it gives up (which may be never).

Parameters
  • from (Q) – [in] start configuration for path.

  • to (rw::math::Transform3D< double >) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.PlannerConstraint(*args)

Bases: object

A tuple of (QConstraintPtr, QEdgeConstraintPtr).

A planner constraint is a small copyable object containing pointers to a configuration constraint and an edge constraint. Sampling based path planners and path optimizers typically use a PlannerConstraint object for the collision checking for the paths.

A number of make() utility constructors are provided for applications where defaults for configuration and edge constraints can be used.

__init__(*args)

Overload 1:

Default constructed without constraints initialized


Overload 2:

A (QConstraintPtr, QEdgeConstraintPtr) tuple.

The constraints must be non-null.

getQConstraint()

The configuration constraint.

getQConstraintPtr()

The configuration constraint pointer.

getQEdgeConstraint()

The edge constraint.

getQEdgeConstraintPtr()

The edge constraint pointer.

inCollision(*args)

Overload 1:

Forwards call to the QConstraint wrapped by the PlannerConstraint


Overload 2:

Forwards call to the QEdgeConstraint wrapped by the PlannerConstraint

static make(*args)

Overload 1:

A (QConstraintPtr, QEdgeConstraintPtr) tuple.

This is equivalent to the standard constructor.


Overload 2:

Planner constraint for a collision detector.

Path are checked discretely for a default device dependent resolution.


Overload 3:

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.


Overload 4:

Planner constraint for a collision strategy and collision

setup.

Path are checked discretely for a default device dependent resolution.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.PlannerConstraintCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

getDeref()

Member access operator.

getQConstraint()

The configuration constraint.

getQConstraintPtr()

The configuration constraint pointer.

getQEdgeConstraint()

The edge constraint.

getQEdgeConstraintPtr()

The edge constraint pointer.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.PlannerConstraintPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

getDeref()

Member access operator.

getQConstraint()

The configuration constraint.

getQConstraintPtr()

The configuration constraint pointer.

getQEdgeConstraint()

The edge constraint.

getQEdgeConstraintPtr()

The edge constraint pointer.

inCollision(*args)

Overload 1:

Forwards call to the QConstraint wrapped by the PlannerConstraint


Overload 2:

Forwards call to the QEdgeConstraint wrapped by the PlannerConstraint

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

make(*args)

Overload 1:

A (QConstraintPtr, QEdgeConstraintPtr) tuple.

This is equivalent to the standard constructor.


Overload 2:

Planner constraint for a collision detector.

Path are checked discretely for a default device dependent resolution.


Overload 3:

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.


Overload 4:

Planner constraint for a collision strategy and collision

setup.

Path are checked discretely for a default device dependent resolution.

property thisown

The membership flag

sdurw_pathplanning.sdurw_pathplanning.PlannerConstraint_make(*args)

Overload 1:

A (QConstraintPtr, QEdgeConstraintPtr) tuple.

This is equivalent to the standard constructor.


Overload 2:

Planner constraint for a collision detector.

Path are checked discretely for a default device dependent resolution.


Overload 3:

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.


Overload 4:

Planner constraint for a collision strategy and collision

setup.

Path are checked discretely for a default device dependent resolution.

class sdurw_pathplanning.sdurw_pathplanning.PlannerUtil(*args, **kwargs)

Bases: object

PlannerUtil provides various utilities useful in path planning

AVERAGE = 1

Estimate weights corresponding to the average distance

WORSTCASE = 0

Estimate weights corresponding to the maximal distance

__init__(*args, **kwargs)
static clampPosition(*args)

Overload 1:

Clamps values to be within bounds

The method treats all joints individually and clamps them to be within the position bounds of the device

Parameters
  • device (Device) – [in] The device for the configurations.

  • q (Q) – [in] Configuration to clamp

Return type

Q

Returns

The clamped configuration


Overload 2:

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.

Parameters
  • bounds (QBox) – [in] The bounds of the configuration space

  • q (Q) – [in] Configuration to clamp

Return type

Q

Returns

The clamped configuration

static estimateMotionWeights(device, frame, initialState, type, samples)

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.

Parameters
  • device (Device) – [in] Device to estimate weights for

  • frame (rw::core::Ptr< rw::kinematics::Frame const >) – [in] Frame to calculate weights for. If null the device end frame will be used

  • initialState (State) – [in] Initial state to use in estimation

  • type (int) – [in] The estimation type

  • samples (int) – [in] The number of samples to use (default 1000)

Return type

Q

Returns

Weights representing the distance

static inCollision(*args)

Overload 1:

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. :rtype: boolean :return: true iff path is in collision.


Overload 2:

Collision checking for a segment.

Parameters
  • start (Q) – [in] Start of segment

  • end (Q) – [in] End of segment

  • constraint (PlannerConstraint) – [in] Constraint for segment

  • checkStart (boolean, optional) – [in] Check start configuration for collision.

  • checkEnd (boolean, optional) – [in] Check end configuration for collision.


Overload 3:

Collision checking for a segment.

Parameters
  • start (Q) – [in] Start of segment

  • end (Q) – [in] End of segment

  • constraint (PlannerConstraint) – [in] Constraint for segment

  • checkStart (boolean, optional) – [in] Check start configuration for collision.

  • checkEnd – [in] Check end configuration for collision.


Overload 4:

Collision checking for a segment.

Parameters
  • start (Q) – [in] Start of segment

  • end (Q) – [in] End of segment

  • constraint (PlannerConstraint) – [in] Constraint for segment

  • checkStart – [in] Check start configuration for collision.

  • checkEnd – [in] Check end configuration for collision.


Overload 5:

Collision checking for a configuration.

Parameters
  • constraint (PlannerConstraint) – [in] Collision checking constraint.

  • q (Q) – [in] Configuration to check for collisions.

static normalizingInfinityMetric(bounds, length=1)

Weighted infinity metric that maps the maps the longest vector in the configuration space to a given length.

Parameters
  • bounds (QBox) – [in] Lower and upper corner of the configuration space.

  • length (float, optional) – [in] The wanted distance between lower and upper corner.

Return type

Ptr

Returns

Metric for which the distance from lower to upper corner equals length.

property thisown

The membership flag

static timeMetric(*args)

Overload 1:

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.


Overload 2:

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.

sdurw_pathplanning.sdurw_pathplanning.PlannerUtil_clampPosition(*args)

Overload 1:

Clamps values to be within bounds

The method treats all joints individually and clamps them to be within the position bounds of the device

Parameters
  • device (Device) – [in] The device for the configurations.

  • q (Q) – [in] Configuration to clamp

Return type

Q

Returns

The clamped configuration


Overload 2:

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.

Parameters
  • bounds (QBox) – [in] The bounds of the configuration space

  • q (Q) – [in] Configuration to clamp

Return type

Q

Returns

The clamped configuration

sdurw_pathplanning.sdurw_pathplanning.PlannerUtil_estimateMotionWeights(device, frame, initialState, type, samples)

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.

Parameters
  • device (Device) – [in] Device to estimate weights for

  • frame (rw::core::Ptr< rw::kinematics::Frame const >) – [in] Frame to calculate weights for. If null the device end frame will be used

  • initialState (State) – [in] Initial state to use in estimation

  • type (int) – [in] The estimation type

  • samples (int) – [in] The number of samples to use (default 1000)

Return type

Q

Returns

Weights representing the distance

sdurw_pathplanning.sdurw_pathplanning.PlannerUtil_inCollision(*args)

Overload 1:

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. :rtype: boolean :return: true iff path is in collision.


Overload 2:

Collision checking for a segment.

Parameters
  • start (Q) – [in] Start of segment

  • end (Q) – [in] End of segment

  • constraint (PlannerConstraint) – [in] Constraint for segment

  • checkStart (boolean, optional) – [in] Check start configuration for collision.

  • checkEnd (boolean, optional) – [in] Check end configuration for collision.


Overload 3:

Collision checking for a segment.

Parameters
  • start (Q) – [in] Start of segment

  • end (Q) – [in] End of segment

  • constraint (PlannerConstraint) – [in] Constraint for segment

  • checkStart (boolean, optional) – [in] Check start configuration for collision.

  • checkEnd – [in] Check end configuration for collision.


Overload 4:

Collision checking for a segment.

Parameters
  • start (Q) – [in] Start of segment

  • end (Q) – [in] End of segment

  • constraint (PlannerConstraint) – [in] Constraint for segment

  • checkStart – [in] Check start configuration for collision.

  • checkEnd – [in] Check end configuration for collision.


Overload 5:

Collision checking for a configuration.

Parameters
  • constraint (PlannerConstraint) – [in] Collision checking constraint.

  • q (Q) – [in] Configuration to check for collisions.

sdurw_pathplanning.sdurw_pathplanning.PlannerUtil_normalizingInfinityMetric(bounds, length=1)

Weighted infinity metric that maps the maps the longest vector in the configuration space to a given length.

Parameters
  • bounds (QBox) – [in] Lower and upper corner of the configuration space.

  • length (float, optional) – [in] The wanted distance between lower and upper corner.

Return type

Ptr

Returns

Metric for which the distance from lower to upper corner equals length.

sdurw_pathplanning.sdurw_pathplanning.PlannerUtil_timeMetric(*args)

Overload 1:

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.


Overload 2:

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.

class sdurw_pathplanning.sdurw_pathplanning.QConstraint(*args, **kwargs)

Bases: object

Interface for the checking for collisions for work cell states.

__init__(*args, **kwargs)
inCollision(q)

True if the work cell is considered to be in collision for the device configuration q.

static make(*args)

Overload 1:

Map a state constraint to a configuration constraint.


Overload 2:

Map a collision detector to a configuration constraint.

static makeBounds(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 makeFixed(value)

A fixed constraint. The fixed constraint always returns value from inCollision().

static makeMerged(*args)

Overload 1:

Combine a set of configuration constraints into a single configuration constraint.


Overload 2:

Combine a pair of configuration constraints into a single configuration constraint.

static makeNormalized(*args)

Overload 1:

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.


Overload 2:

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.


Overload 3:

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.

setLog(log)

Set the log to be used for writing debug info :type log: Ptr :param log: [in] Log to which debug information is to be written

property thisown

The membership flag

update(state)

Updates the constraint with a new state

The method might not have an effect on all constrainttypes.

class sdurw_pathplanning.sdurw_pathplanning.QConstraintCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

getDeref()

Member access operator.

inCollision(q)

True if the work cell is considered to be in collision for the device configuration q.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QConstraintPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

getDeref()

Member access operator.

inCollision(q)

True if the work cell is considered to be in collision for the device configuration q.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

make(*args)

Overload 1:

Map a state constraint to a configuration constraint.


Overload 2:

Map a collision detector to a configuration constraint.

makeBounds(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.

makeFixed(value)

A fixed constraint. The fixed constraint always returns value from inCollision().

makeMerged(*args)

Overload 1:

Combine a set of configuration constraints into a single configuration constraint.


Overload 2:

Combine a pair of configuration constraints into a single configuration constraint.

makeNormalized(*args)

Overload 1:

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.


Overload 2:

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.


Overload 3:

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.

setLog(log)

Set the log to be used for writing debug info :type log: Ptr :param log: [in] Log to which debug information is to be written

property thisown

The membership flag

update(state)

Updates the constraint with a new state

The method might not have an effect on all constrainttypes.

sdurw_pathplanning.sdurw_pathplanning.QConstraint_make(*args)

Overload 1:

Map a state constraint to a configuration constraint.


Overload 2:

Map a collision detector to a configuration constraint.

sdurw_pathplanning.sdurw_pathplanning.QConstraint_makeBounds(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.

sdurw_pathplanning.sdurw_pathplanning.QConstraint_makeFixed(value)

A fixed constraint. The fixed constraint always returns value from inCollision().

sdurw_pathplanning.sdurw_pathplanning.QConstraint_makeMerged(*args)

Overload 1:

Combine a set of configuration constraints into a single configuration constraint.


Overload 2:

Combine a pair of configuration constraints into a single configuration constraint.

sdurw_pathplanning.sdurw_pathplanning.QConstraint_makeNormalized(*args)

Overload 1:

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.


Overload 2:

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.


Overload 3:

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.

class sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraint(*args, **kwargs)

Bases: object

Edge constraint interface.

An edge constraint represents a path that connects a pair of configurations and checks if this path can be traversed.

The edge constraint may assume that the start and end configurations are valid (e.g. not colliding).

Each edge has a non-negative cost measuring the degree to which the path connecting the configurations has been verified. You can use the cost measure to for example always verify the edge for which the most of the path still remains to be verified. The exact meaning of the cost is defined by the specific subclass.

Given an edge constraint you can construct a new edge constraint of the same type, but for a new pair of configurations, with QEdgeConstraint::instance().

__init__(*args, **kwargs)
inCollision(start, end)

True if the path from start to end can’t be traversed.

Parameters
  • start (Q) – [in] Start configuration.

  • end (Q) – [in] End configuration.

static make(constraint, metric, resolution)

Discrete path verification for a linearly interpolated path.

Performs a binary style checking of the edge with a resolution of resolution.

The length of the edge is virtually extended to exactly match the specified

resolution. However, only configurations within the original length are tested.

Each configuration tested is checked using constraint.

The metric must be well-behaved, i.e. linear.

Start and end configurations are assumed to be collision free.

type constraint

rw::core::Ptr< rw::pathplanning::QConstraint >

param constraint

[in] Constraint to check configurations with

type metric

CPtr

param metric

[in] Metric with which the resolution it to be measured

type resolution

float

param resolution

[in] The test resolution

static makeDefault(constraint, device)

Default edge constraint for a configuration constraint and a device.

Start and end configurations are connected by a straight line in the configuration space and are checked by a default collision checking resolution.

static makeMerged(*args)

Overload 1:

Makes an edge constraint by combining multiple edge constraints

The constraints provided are called one by one in the order provided. It is assumed that all constraints matches the same device.

Parameters

constraints (std::vector< rw::pathplanning::QEdgeConstraint::Ptr >) – [in] List of constraints to check

Return type

Ptr

Returns

Pointer to the resulting QEdgeConstraint. Pointer has ownership.


Overload 2:

Makes an edge constraint by combining two edge constraints

The constraints provided are called one by one in the order provided. It is assumed that all constraints matches the same device.

Parameters
  • constraint1 (Ptr) – [in] First constraint to check

  • constraint2 (Ptr) – [in] Second constraint to check

Return type

Ptr

Returns

Pointer to the resulting QEdgeConstraint. Pointer has ownership.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraintCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

getDeref()

Member access operator.

inCollision(start, end)

True if the path from start to end can’t be traversed.

Parameters
  • start (Q) – [in] Start configuration.

  • end (Q) – [in] End configuration.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraintIncremental(*args, **kwargs)

Bases: object

Edge constraint interface for incremental testing of an edge

An edge constraint represents a path that connects a pair of configurations and checks if this path can be traversed.

The edge constraint may assume that the start and end configurations are valid (e.g. not colliding).

Each edge has a non-negative cost measuring the degree to which the path connecting the configurations has been verified. You can use the cost measure to for example always verify the edge for which the most of the path still remains to be verified. The exact meaning of the cost is defined by the specific subclass.

Given an edge planner you can construct a new edge planner of the same type, but for a new pair of configurations, with QEdgeConstraint::instance().

__init__(*args, **kwargs)
getEnd()

The end configuration of the path.

getStart()

The start configuration of the path.

inCollision(*args)

Overload 1:

True if the path from start to end can’t be traversed.

Parameters
  • start (Q) – [in] Start configuration.

  • end (Q) – [in] End configuration.


Overload 2:

True if the path connecting the start and end configuration can’t be traversed.

inCollisionCost()

Non-negative measure of the amount of the path that still remains to be verified.

The exact definition of the cost is decided by the subclass.

The cost of an edge should strictly decrease for every call of verifyIncrement().

The cost of a fully verified edge can be 0, but does not have to be.

inCollisionPartialCheck()

Perform a partial check of the path and return true if a collision was found.

Full check of the path can be implemented in terms of a sequence of partial checks. The isFullyChecked() method returns true when there are no more partial checks to be done.

instance(start, end)

An edge constraint for a pair of configurations.

Parameters
  • start (Q) – [in] Start configuration of path

  • end (Q) – [in] End configuration of path

isFullyChecked()

True if the path has been fully checked.

To check a path, either call inCollision() or repeatedly call inCollisionPartialCheck() until inCollisionPartialCheck() returns false or isFullyChecked() returns true.

static make(constraint, metric, resolution=1)

Discrete path verification for a linearly interpolated path.

Linearly interpolate from start to end configuration until the distance between pairs of configurations is resolution when measured by metric. Verify each configuration by constraint.

The cost is defined as the distance (measured by metric) between pairs of configurations currently verified by constraint.

The metric must be well-behaved, i.e. linear.

You can pass empty configurations as start and end to construct an initial edge planner that you can instance() with better configurations later.

Start and end configurations for this initial planner are set to the empty configuration.

static makeDefault(constraint, device)

Default edge constraint for a configuration constraint and a device.

Start and end configurations are connected by a straight line in the configuration space and are checked by a default collision checking resolution.

static makeFixed(value)

A fixed edge constraint.

The fixed edge constraint always returns value from inCollision().

reset(start, end)

Reset the object to use a different pair of start and end configurations.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraintIncrementalPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

getDeref()

Member access operator.

getEnd()

The end configuration of the path.

getStart()

The start configuration of the path.

inCollision(*args)

Overload 1:

True if the path from start to end can’t be traversed.

Parameters
  • start (Q) – [in] Start configuration.

  • end (Q) – [in] End configuration.


Overload 2:

True if the path connecting the start and end configuration can’t be traversed.

inCollisionCost()

Non-negative measure of the amount of the path that still remains to be verified.

The exact definition of the cost is decided by the subclass.

The cost of an edge should strictly decrease for every call of verifyIncrement().

The cost of a fully verified edge can be 0, but does not have to be.

inCollisionPartialCheck()

Perform a partial check of the path and return true if a collision was found.

Full check of the path can be implemented in terms of a sequence of partial checks. The isFullyChecked() method returns true when there are no more partial checks to be done.

instance(start, end)

An edge constraint for a pair of configurations.

Parameters
  • start (Q) – [in] Start configuration of path

  • end (Q) – [in] End configuration of path

isFullyChecked()

True if the path has been fully checked.

To check a path, either call inCollision() or repeatedly call inCollisionPartialCheck() until inCollisionPartialCheck() returns false or isFullyChecked() returns true.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

make(constraint, metric, resolution=1)

Discrete path verification for a linearly interpolated path.

Linearly interpolate from start to end configuration until the distance between pairs of configurations is resolution when measured by metric. Verify each configuration by constraint.

The cost is defined as the distance (measured by metric) between pairs of configurations currently verified by constraint.

The metric must be well-behaved, i.e. linear.

You can pass empty configurations as start and end to construct an initial edge planner that you can instance() with better configurations later.

Start and end configurations for this initial planner are set to the empty configuration.

makeDefault(constraint, device)

Default edge constraint for a configuration constraint and a device.

Start and end configurations are connected by a straight line in the configuration space and are checked by a default collision checking resolution.

makeFixed(value)

A fixed edge constraint.

The fixed edge constraint always returns value from inCollision().

reset(start, end)

Reset the object to use a different pair of start and end configurations.

property thisown

The membership flag

sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraintIncremental_make(constraint, metric, resolution=1)

Discrete path verification for a linearly interpolated path.

Linearly interpolate from start to end configuration until the distance between pairs of configurations is resolution when measured by metric. Verify each configuration by constraint.

The cost is defined as the distance (measured by metric) between pairs of configurations currently verified by constraint.

The metric must be well-behaved, i.e. linear.

You can pass empty configurations as start and end to construct an initial edge planner that you can instance() with better configurations later.

Start and end configurations for this initial planner are set to the empty configuration.

sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraintIncremental_makeDefault(constraint, device)

Default edge constraint for a configuration constraint and a device.

Start and end configurations are connected by a straight line in the configuration space and are checked by a default collision checking resolution.

sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraintIncremental_makeFixed(value)

A fixed edge constraint.

The fixed edge constraint always returns value from inCollision().

class sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraintPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

getDeref()

Member access operator.

inCollision(start, end)

True if the path from start to end can’t be traversed.

Parameters
  • start (Q) – [in] Start configuration.

  • end (Q) – [in] End configuration.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

make(constraint, metric, resolution)

Discrete path verification for a linearly interpolated path.

Performs a binary style checking of the edge with a resolution of resolution.

The length of the edge is virtually extended to exactly match the specified

resolution. However, only configurations within the original length are tested.

Each configuration tested is checked using constraint.

The metric must be well-behaved, i.e. linear.

Start and end configurations are assumed to be collision free.

type constraint

rw::core::Ptr< rw::pathplanning::QConstraint >

param constraint

[in] Constraint to check configurations with

type metric

CPtr

param metric

[in] Metric with which the resolution it to be measured

type resolution

float

param resolution

[in] The test resolution

makeDefault(constraint, device)

Default edge constraint for a configuration constraint and a device.

Start and end configurations are connected by a straight line in the configuration space and are checked by a default collision checking resolution.

makeMerged(*args)

Overload 1:

Makes an edge constraint by combining multiple edge constraints

The constraints provided are called one by one in the order provided. It is assumed that all constraints matches the same device.

Parameters

constraints (std::vector< rw::pathplanning::QEdgeConstraint::Ptr >) – [in] List of constraints to check

Return type

Ptr

Returns

Pointer to the resulting QEdgeConstraint. Pointer has ownership.


Overload 2:

Makes an edge constraint by combining two edge constraints

The constraints provided are called one by one in the order provided. It is assumed that all constraints matches the same device.

Parameters
  • constraint1 (Ptr) – [in] First constraint to check

  • constraint2 (Ptr) – [in] Second constraint to check

Return type

Ptr

Returns

Pointer to the resulting QEdgeConstraint. Pointer has ownership.

property thisown

The membership flag

sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraint_make(constraint, metric, resolution)

Discrete path verification for a linearly interpolated path.

Performs a binary style checking of the edge with a resolution of resolution.

The length of the edge is virtually extended to exactly match the specified

resolution. However, only configurations within the original length are tested.

Each configuration tested is checked using constraint.

The metric must be well-behaved, i.e. linear.

Start and end configurations are assumed to be collision free.

type constraint

rw::core::Ptr< rw::pathplanning::QConstraint >

param constraint

[in] Constraint to check configurations with

type metric

CPtr

param metric

[in] Metric with which the resolution it to be measured

type resolution

float

param resolution

[in] The test resolution

sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraint_makeDefault(constraint, device)

Default edge constraint for a configuration constraint and a device.

Start and end configurations are connected by a straight line in the configuration space and are checked by a default collision checking resolution.

sdurw_pathplanning.sdurw_pathplanning.QEdgeConstraint_makeMerged(*args)

Overload 1:

Makes an edge constraint by combining multiple edge constraints

The constraints provided are called one by one in the order provided. It is assumed that all constraints matches the same device.

Parameters

constraints (std::vector< rw::pathplanning::QEdgeConstraint::Ptr >) – [in] List of constraints to check

Return type

Ptr

Returns

Pointer to the resulting QEdgeConstraint. Pointer has ownership.


Overload 2:

Makes an edge constraint by combining two edge constraints

The constraints provided are called one by one in the order provided. It is assumed that all constraints matches the same device.

Parameters
  • constraint1 (Ptr) – [in] First constraint to check

  • constraint2 (Ptr) – [in] Second constraint to check

Return type

Ptr

Returns

Pointer to the resulting QEdgeConstraint. Pointer has ownership.

class sdurw_pathplanning.sdurw_pathplanning.QIKSampler(*args, **kwargs)

Bases: object

Interface for the sampling a configuration that solves an IK problem.

__init__(*args, **kwargs)
empty()

True if the sampler is known to contain no more configurations.

static make(device, state, solver=0, seed=0, maxAttempts=-1)

An IK sampler based on an iterative IK solver.

All solutions returned are checked to be within the bounds of the device.

type device

rw::core::Ptr< rw::models::Device >

param device

[in] The device for which seeds are sampled.

type state

State

param state

[in] Fixed state with respect to which IK is solved.

type solver

rw::core::Ptr< rw::invkin::IterativeIK >, optional

param solver

[in] Optional IK solver for device and state.

type seed

rw::core::Ptr< rw::pathplanning::QSampler >, optional

param seed

[in] Optional sampler of seeds to feed the IK solver.

type maxAttempts

int, optional

param maxAttempts

[in] Optional number of seeds to feed the IK solver. If maxAttempts is negative, a default value for

maxAttempts is chosen.

static makeConstrained(sampler, constraint, maxAttempts=-1)

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.

sample(target)

Sample a configuration that solves an IK problem for

target.

If sampling fails, the sampler may return the empty configuration. If empty() is true then the sampler has no more configurations. Otherwise sample() may (or may not) succeed if called a second time.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QIKSamplerCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

empty()

True if the sampler is known to contain no more configurations.

getDeref()

Member access operator.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QIKSamplerPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

empty()

True if the sampler is known to contain no more configurations.

getDeref()

Member access operator.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

make(device, state, solver=0, seed=0, maxAttempts=-1)

An IK sampler based on an iterative IK solver.

All solutions returned are checked to be within the bounds of the device.

type device

rw::core::Ptr< rw::models::Device >

param device

[in] The device for which seeds are sampled.

type state

State

param state

[in] Fixed state with respect to which IK is solved.

type solver

rw::core::Ptr< rw::invkin::IterativeIK >, optional

param solver

[in] Optional IK solver for device and state.

type seed

rw::core::Ptr< rw::pathplanning::QSampler >, optional

param seed

[in] Optional sampler of seeds to feed the IK solver.

type maxAttempts

int, optional

param maxAttempts

[in] Optional number of seeds to feed the IK solver. If maxAttempts is negative, a default value for

maxAttempts is chosen.

makeConstrained(sampler, constraint, maxAttempts=-1)

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.

sample(target)

Sample a configuration that solves an IK problem for

target.

If sampling fails, the sampler may return the empty configuration. If empty() is true then the sampler has no more configurations. Otherwise sample() may (or may not) succeed if called a second time.

property thisown

The membership flag

sdurw_pathplanning.sdurw_pathplanning.QIKSampler_make(device, state, solver=0, seed=0, maxAttempts=-1)

An IK sampler based on an iterative IK solver.

All solutions returned are checked to be within the bounds of the device.

type device

rw::core::Ptr< rw::models::Device >

param device

[in] The device for which seeds are sampled.

type state

State

param state

[in] Fixed state with respect to which IK is solved.

type solver

rw::core::Ptr< rw::invkin::IterativeIK >, optional

param solver

[in] Optional IK solver for device and state.

type seed

rw::core::Ptr< rw::pathplanning::QSampler >, optional

param seed

[in] Optional sampler of seeds to feed the IK solver.

type maxAttempts

int, optional

param maxAttempts

[in] Optional number of seeds to feed the IK solver. If maxAttempts is negative, a default value for

maxAttempts is chosen.

sdurw_pathplanning.sdurw_pathplanning.QIKSampler_makeConstrained(sampler, constraint, maxAttempts=-1)

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.

class sdurw_pathplanning.sdurw_pathplanning.QNormalizer(bounds)

Bases: object

Normalization of configurations.

QNormalizer linearly maps configurations of a rectangular configuration space into a square configuration space with lower corner (0, 0, …, 0) and upper corner (1, 1, …, 1).

__init__(bounds)

Normalizer for the configuration space box given by bounds.

fromNormalized(q)

Convert from a normalized configuration to a real configuration.

getBounds()

The box of the configuration space with respect to which normalization is done.

static identity()

Normalizer for the already normalized configuration space box.

setFromNormalized(q)

Convert from a normalized configuration to a real configuration and assign the real configuration to q.

setToNormalized(q)

Convert a real configuration to a normalized configuration and write the normalized configuration to q.

property thisown

The membership flag

toNormalized(q)

Convert a real configuration to a normalized configuration.

class sdurw_pathplanning.sdurw_pathplanning.QNormalizerCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

fromNormalized(q)

Convert from a normalized configuration to a real configuration.

getBounds()

The box of the configuration space with respect to which normalization is done.

getDeref()

Member access operator.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

setFromNormalized(q)

Convert from a normalized configuration to a real configuration and assign the real configuration to q.

setToNormalized(q)

Convert a real configuration to a normalized configuration and write the normalized configuration to q.

property thisown

The membership flag

toNormalized(q)

Convert a real configuration to a normalized configuration.

class sdurw_pathplanning.sdurw_pathplanning.QNormalizerPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

fromNormalized(q)

Convert from a normalized configuration to a real configuration.

getBounds()

The box of the configuration space with respect to which normalization is done.

getDeref()

Member access operator.

identity()

Normalizer for the already normalized configuration space box.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

setFromNormalized(q)

Convert from a normalized configuration to a real configuration and assign the real configuration to q.

setToNormalized(q)

Convert a real configuration to a normalized configuration and write the normalized configuration to q.

property thisown

The membership flag

toNormalized(q)

Convert a real configuration to a normalized configuration.

sdurw_pathplanning.sdurw_pathplanning.QNormalizer_identity()

Normalizer for the already normalized configuration space box.

class sdurw_pathplanning.sdurw_pathplanning.QSampler(*args, **kwargs)

Bases: object

Interface for the sampling a configuration.

__init__(*args, **kwargs)
empty()

True if the sampler is known to contain no more configurations.

static make(sampler, target)

A sampler of IK solutions for a specific target.

Parameters
  • sampler (rw::core::Ptr< rw::pathplanning::QIKSampler >) – [in] Sampler of IK solutions for target.

  • target (rw::math::Transform3D< double >) – [in] Target for IK solver.

static makeBoxDirectionSampler(bounds)

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 makeConstrained(sampler, constraint, maxAttempts=-1)

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 makeEmpty()

Empty sampler.

static makeFinite(*args)

Overload 1:

Sampler for the values of a finite sequence.

sample() returns each of the values of qs in order. When all of these samples have been returned, empty() returns true and sample() returns the empty configuration.


Overload 2:

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 makeFixed(q)

Sampler that always returns the same configuration.

The sampler is considered never empty (empty() always returns false).

static makeNormalized(sampler, normalizer)

Map a sampler of standard configurations into a sampler of normalized configurations.

static makeSingle(q)

Sampler that always returns a single configuration.

The sample() returns q the first time the method is called and the empty configuration otherwise. empty() returns true after the first call of sample().

static makeUniform(*args)

Overload 1:

Uniform random sampling for a box of the configuration space.


Overload 2:

Uniform random sampling for a device.


Overload 3:

Uniform random sampling for a device.

sample()

Sample a configuration.

If sampling fails, the sampler may return the empty configuration. If empty() is true then the sampler has no more configurations. Otherwise sample() may (or may not) succeed if called a second time.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QSamplerCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

empty()

True if the sampler is known to contain no more configurations.

getDeref()

Member access operator.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QSamplerPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

empty()

True if the sampler is known to contain no more configurations.

getDeref()

Member access operator.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

make(sampler, target)

A sampler of IK solutions for a specific target.

Parameters
  • sampler (rw::core::Ptr< rw::pathplanning::QIKSampler >) – [in] Sampler of IK solutions for target.

  • target (rw::math::Transform3D< double >) – [in] Target for IK solver.

makeBoxDirectionSampler(bounds)

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.

makeConstrained(sampler, constraint, maxAttempts=-1)

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.

makeEmpty()

Empty sampler.

makeFinite(*args)

Overload 1:

Sampler for the values of a finite sequence.

sample() returns each of the values of qs in order. When all of these samples have been returned, empty() returns true and sample() returns the empty configuration.


Overload 2:

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.

makeFixed(q)

Sampler that always returns the same configuration.

The sampler is considered never empty (empty() always returns false).

makeNormalized(sampler, normalizer)

Map a sampler of standard configurations into a sampler of normalized configurations.

makeSingle(q)

Sampler that always returns a single configuration.

The sample() returns q the first time the method is called and the empty configuration otherwise. empty() returns true after the first call of sample().

makeUniform(*args)

Overload 1:

Uniform random sampling for a box of the configuration space.


Overload 2:

Uniform random sampling for a device.


Overload 3:

Uniform random sampling for a device.

sample()

Sample a configuration.

If sampling fails, the sampler may return the empty configuration. If empty() is true then the sampler has no more configurations. Otherwise sample() may (or may not) succeed if called a second time.

property thisown

The membership flag

sdurw_pathplanning.sdurw_pathplanning.QSampler_make(sampler, target)

A sampler of IK solutions for a specific target.

Parameters
  • sampler (rw::core::Ptr< rw::pathplanning::QIKSampler >) – [in] Sampler of IK solutions for target.

  • target (rw::math::Transform3D< double >) – [in] Target for IK solver.

sdurw_pathplanning.sdurw_pathplanning.QSampler_makeBoxDirectionSampler(bounds)

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.

sdurw_pathplanning.sdurw_pathplanning.QSampler_makeConstrained(sampler, constraint, maxAttempts=-1)

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.

sdurw_pathplanning.sdurw_pathplanning.QSampler_makeEmpty()

Empty sampler.

sdurw_pathplanning.sdurw_pathplanning.QSampler_makeFinite(*args)

Overload 1:

Sampler for the values of a finite sequence.

sample() returns each of the values of qs in order. When all of these samples have been returned, empty() returns true and sample() returns the empty configuration.


Overload 2:

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.

sdurw_pathplanning.sdurw_pathplanning.QSampler_makeFixed(q)

Sampler that always returns the same configuration.

The sampler is considered never empty (empty() always returns false).

sdurw_pathplanning.sdurw_pathplanning.QSampler_makeNormalized(sampler, normalizer)

Map a sampler of standard configurations into a sampler of normalized configurations.

sdurw_pathplanning.sdurw_pathplanning.QSampler_makeSingle(q)

Sampler that always returns a single configuration.

The sample() returns q the first time the method is called and the empty configuration otherwise. empty() returns true after the first call of sample().

sdurw_pathplanning.sdurw_pathplanning.QSampler_makeUniform(*args)

Overload 1:

Uniform random sampling for a box of the configuration space.


Overload 2:

Uniform random sampling for a device.


Overload 3:

Uniform random sampling for a device.

class sdurw_pathplanning.sdurw_pathplanning.QToQPlanner(*args, **kwargs)

Bases: PathPlannerQQ

Path planner interface.

A path planner plans a path in the configuration space from a start configuration to a goal configuration.

__init__(*args, **kwargs)
static make(*args)

Overload 1:

Construct a path planner from a region planner.

The region planner is given as goal region the single to configuration passed to the query() method.

Parameters

planner (rw::core::Ptr< rw::pathplanning::QToQSamplerPlanner >) – [in] A planner for a region given by a QSampler.


Overload 2:

Construct a path planner from an edge constraint.

The path planners calls the edge constraint to verify if the path going directly from the start to goal configuration can be traversed.

The configuration constraint is called to verify that neither the start nor end configuration is in collision.

Parameters

constraint (PlannerConstraint) – [in] Planner constraint.

Return type

Ptr

Returns

A planner that attempts the directly connecting edge only.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QToQPlannerCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

getDeref()

Member access operator.

getProperties(*args)

Overload 1:

Property map for the planner.


Overload 2:

Property map for the planner.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QToQPlannerPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

getDeref()

Member access operator.

getProperties(*args)

Overload 1:

Property map for the planner.


Overload 2:

Property map for the planner.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

make(*args)

Overload 1:

Construct a path planner from a region planner.

The region planner is given as goal region the single to configuration passed to the query() method.

Parameters

planner (rw::core::Ptr< rw::pathplanning::QToQSamplerPlanner >) – [in] A planner for a region given by a QSampler.


Overload 2:

Construct a path planner from an edge constraint.

The path planners calls the edge constraint to verify if the path going directly from the start to goal configuration can be traversed.

The configuration constraint is called to verify that neither the start nor end configuration is in collision.

Parameters

constraint (PlannerConstraint) – [in] Planner constraint.

Return type

Ptr

Returns

A planner that attempts the directly connecting edge only.

query(*args)

Overload 1:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (Q) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • stop (StopCriteria) – [in] Abort the planning when stop returns true.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 2:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (Q) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • time (float) – [in] Abort the planning after time seconds.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 3:

Plan a path from the configuration from to the destination to.

The planner runs until it gives up (which may be never).

Parameters
  • from (Q) – [in] start configuration for path.

  • to (Q) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.

property thisown

The membership flag

sdurw_pathplanning.sdurw_pathplanning.QToQPlanner_make(*args)

Overload 1:

Construct a path planner from a region planner.

The region planner is given as goal region the single to configuration passed to the query() method.

Parameters

planner (rw::core::Ptr< rw::pathplanning::QToQSamplerPlanner >) – [in] A planner for a region given by a QSampler.


Overload 2:

Construct a path planner from an edge constraint.

The path planners calls the edge constraint to verify if the path going directly from the start to goal configuration can be traversed.

The configuration constraint is called to verify that neither the start nor end configuration is in collision.

Parameters

constraint (PlannerConstraint) – [in] Planner constraint.

Return type

Ptr

Returns

A planner that attempts the directly connecting edge only.

class sdurw_pathplanning.sdurw_pathplanning.QToQSamplerPlanner(*args, **kwargs)

Bases: PathPlannerQQSampler

Sampled region planner interface.

QToQSamplerPlanner plans a configuration space path from a start configuration to any configuration in the set represented by a sampler.

__init__(*args, **kwargs)
property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QToQSamplerPlannerCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

getDeref()

Member access operator.

getProperties(*args)

Overload 1:

Property map for the planner.


Overload 2:

Property map for the planner.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QToQSamplerPlannerPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

getDeref()

Member access operator.

getProperties(*args)

Overload 1:

Property map for the planner.


Overload 2:

Property map for the planner.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

query(*args)

Overload 1:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (QSampler) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • stop (StopCriteria) – [in] Abort the planning when stop returns true.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 2:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (QSampler) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • time (float) – [in] Abort the planning after time seconds.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 3:

Plan a path from the configuration from to the destination to.

The planner runs until it gives up (which may be never).

Parameters
  • from (Q) – [in] start configuration for path.

  • to (QSampler) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QToTPlanner(*args, **kwargs)

Bases: PathPlannerQTransform3D

Approach planner interface.

An approach planner plans a path from a configuration for the device to a configuration for the tool.

__init__(*args, **kwargs)
getProperties()

Overload 1:

Property map for the planner.


Overload 2:

Property map for the planner.

static make(planner, ikSampler)

An approach planner for a sampler of IK solutions and a region planner.

Target configurations are sampled by ikSampler and fed to

planner.

type planner

rw::core::Ptr< rw::pathplanning::QToQSamplerPlanner >

param planner

[in] Planner for a QSampler region.

type ikSampler

rw::core::Ptr< rw::pathplanning::QIKSampler >

param ikSampler

[in] Sampler of IK solutions for the target transform.

static makeToNearest(planner, sampler, metric, cnt)

An approach planner for a standard path planner and a sampler of IK solutions.

For each query(from, to) call, the planner extracts cnt samples from sampler and calls planner with the configuration closest to from according to metric.

query(*args)

Overload 1:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (rw::math::Transform3D< double >) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • stop (StopCriteria) – [in] Abort the planning when stop returns true.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 2:

Plan a path from the configuration from to the destination to.

Parameters
  • from (Q) – [in] start configuration for path.

  • to (rw::math::Transform3D< double >) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

  • time (float) – [in] Abort the planning after time seconds.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.


Overload 3:

Plan a path from the configuration from to the destination to.

The planner runs until it gives up (which may be never).

Parameters
  • from (Q) – [in] start configuration for path.

  • to (rw::math::Transform3D< double >) – [in] end destination of path.

  • path (rw::trajectory::Path< rw::math::Q >) – [out] a collision free path connecting from to to.

Return type

boolean

Returns

true if a path between from from to to was found and false otherwise.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QToTPlannerCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

getDeref()

Member access operator.

getProperties(*args)

Overload 1:

Property map for the planner.


Overload 2:

Property map for the planner.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.QToTPlannerPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

getDeref()

Member access operator.

getProperties()
isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

make(planner, ikSampler)

An approach planner for a sampler of IK solutions and a region planner.

Target configurations are sampled by ikSampler and fed to

planner.

type planner

rw::core::Ptr< rw::pathplanning::QToQSamplerPlanner >

param planner

[in] Planner for a QSampler region.

type ikSampler

rw::core::Ptr< rw::pathplanning::QIKSampler >

param ikSampler

[in] Sampler of IK solutions for the target transform.

makeToNearest(planner, sampler, metric, cnt)

An approach planner for a standard path planner and a sampler of IK solutions.

For each query(from, to) call, the planner extracts cnt samples from sampler and calls planner with the configuration closest to from according to metric.

query(*args)
property thisown

The membership flag

sdurw_pathplanning.sdurw_pathplanning.QToTPlanner_make(planner, ikSampler)

An approach planner for a sampler of IK solutions and a region planner.

Target configurations are sampled by ikSampler and fed to

planner.

type planner

rw::core::Ptr< rw::pathplanning::QToQSamplerPlanner >

param planner

[in] Planner for a QSampler region.

type ikSampler

rw::core::Ptr< rw::pathplanning::QIKSampler >

param ikSampler

[in] Sampler of IK solutions for the target transform.

sdurw_pathplanning.sdurw_pathplanning.QToTPlanner_makeToNearest(planner, sampler, metric, cnt)

An approach planner for a standard path planner and a sampler of IK solutions.

For each query(from, to) call, the planner extracts cnt samples from sampler and calls planner with the configuration closest to from according to metric.

class sdurw_pathplanning.sdurw_pathplanning.StateConstraint(*args, **kwargs)

Bases: object

Interface for the checking for collisions for work cell states.

__init__(*args, **kwargs)
inCollision(state)

True if the work cell is considered to be in collision for the work cell state state.

static make(*args)

Overload 1:

Map a collision detector to a state constraint.


Overload 2:

Combine a set of state constraints into a single state constraint.

setLog(log)

Set the log to be used for writing debug info :type log: rw::core::Ptr< rw::core::Log > :param log: [in] Log to which debug information is to be written

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.StateConstraintCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

getDeref()

Member access operator.

inCollision(state)

True if the work cell is considered to be in collision for the work cell state state.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.StateConstraintPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

getDeref()

Member access operator.

inCollision(state)

True if the work cell is considered to be in collision for the work cell state state.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

make(*args)

Overload 1:

Map a collision detector to a state constraint.


Overload 2:

Combine a set of state constraints into a single state constraint.

setLog(log)

Set the log to be used for writing debug info :type log: rw::core::Ptr< rw::core::Log > :param log: [in] Log to which debug information is to be written

property thisown

The membership flag

sdurw_pathplanning.sdurw_pathplanning.StateConstraint_make(*args)

Overload 1:

Map a collision detector to a state constraint.


Overload 2:

Combine a set of state constraints into a single state constraint.

class sdurw_pathplanning.sdurw_pathplanning.StopCriteria(*args, **kwargs)

Bases: object

StopCriteria is a class for specifying an instant a compution should be aborted.

The computation determines when to stop by repeatedly polling the StopCriteria::stop() method. Therefore the stop() method should be implemented to have a very short, preferably deterministic running time.

__init__(*args, **kwargs)
instance()

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.

stop()

True is returned when the computation should be stopped.

static stopAfter(time)

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 stopByFlag(stop)

Stop the computation when stop says so.

stop must be non-null.

Ownership of stop is not taken.

static stopByFun(fun)

Stop the computation when fun says so.

static stopCnt(cnt)

Stop the computation after cnt calls of the stop criteria.

static stopEither(*args)

Overload 1:

Stop if either of criteria says stop.


Overload 2:

Stop if either a or b says stop.

static stopNever()

Never stop the computation.

static stopNow()

Immediately stop the computation.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.StopCriteriaCPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

deref()

The pointer stored in the object.

getDeref()

Member access operator.

instance()

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.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

stop()

True is returned when the computation should be stopped.

property thisown

The membership flag

class sdurw_pathplanning.sdurw_pathplanning.StopCriteriaPtr(*args)

Bases: object

Ptr stores a pointer and optionally takes ownership of the value.

__init__(*args)

Overload 1:

Default constructor yielding a NULL-pointer.


Overload 2:

Do not take ownership of ptr.

ptr can be null.

The constructor is implicit on purpose.

cptr()
deref()

The pointer stored in the object.

getDeref()

Member access operator.

instance()

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.

isNull()

checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null

isShared()

check if this Ptr has shared ownership or none ownership :rtype: boolean :return: true if Ptr has shared ownership, false if it has no ownership.

stop()

True is returned when the computation should be stopped.

stopAfter(time)

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.

stopByFlag(stop)

Stop the computation when stop says so.

stop must be non-null.

Ownership of stop is not taken.

stopByFun(fun)

Stop the computation when fun says so.

stopCnt(cnt)

Stop the computation after cnt calls of the stop criteria.

stopEither(*args)

Overload 1:

Stop if either of criteria says stop.


Overload 2:

Stop if either a or b says stop.

stopNever()

Never stop the computation.

stopNow()

Immediately stop the computation.

property thisown

The membership flag

sdurw_pathplanning.sdurw_pathplanning.StopCriteria_stopAfter(time)

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.

sdurw_pathplanning.sdurw_pathplanning.StopCriteria_stopByFlag(stop)

Stop the computation when stop says so.

stop must be non-null.

Ownership of stop is not taken.

sdurw_pathplanning.sdurw_pathplanning.StopCriteria_stopByFun(fun)

Stop the computation when fun says so.

sdurw_pathplanning.sdurw_pathplanning.StopCriteria_stopCnt(cnt)

Stop the computation after cnt calls of the stop criteria.

sdurw_pathplanning.sdurw_pathplanning.StopCriteria_stopEither(*args)

Overload 1:

Stop if either of criteria says stop.


Overload 2:

Stop if either a or b says stop.

sdurw_pathplanning.sdurw_pathplanning.StopCriteria_stopNever()

Never stop the computation.

sdurw_pathplanning.sdurw_pathplanning.StopCriteria_stopNow()

Immediately stop the computation.

class sdurw_pathplanning.sdurw_pathplanning.TimeAnalysis

Bases: object

Result struct for Time analysis

__init__()

Construct TimeAnalysis struct with times initialized to 0

property thisown

The membership flag

property time1

Time to execute path when considering only velocity limits

property time2

Time to execute path when considering both velocity and acceleration limits. NOT IMPLEMENTED YET

class sdurw_pathplanning.sdurw_pathplanning.VectorQConstraintPtr(arg1=None, arg2=None)

Bases: list

This class is deprecated and is basically a wrapper around a list

__init__(arg1=None, arg2=None)
at(i)
back()
clear()

Remove all items from list.

empty()
front()
pop_back()
push_back(elem)
size()
class sdurw_pathplanning.sdurw_pathplanning.VectorQEdgeConstraintPtr(arg1=None, arg2=None)

Bases: list

This class is deprecated and is basically a wrapper around a list

__init__(arg1=None, arg2=None)
at(i)
back()
clear()

Remove all items from list.

empty()
front()
pop_back()
push_back(elem)
size()
class sdurw_pathplanning.sdurw_pathplanning.VectorStateConstraintPtr(arg1=None, arg2=None)

Bases: list

This class is deprecated and is basically a wrapper around a list

__init__(arg1=None, arg2=None)
at(i)
back()
clear()

Remove all items from list.

empty()
front()
pop_back()
push_back(elem)
size()
class sdurw_pathplanning.sdurw_pathplanning.VectorStopCriteriaPtr(arg1=None, arg2=None)

Bases: list

This class is deprecated and is basically a wrapper around a list

__init__(arg1=None, arg2=None)
at(i)
back()
clear()

Remove all items from list.

empty()
front()
pop_back()
push_back(elem)
size()
sdurw_pathplanning.sdurw_pathplanning.ownedPtr(*args)

Overload 1:

A Ptr that takes ownership over a raw pointer ptr.


Overload 2:

A Ptr that takes ownership over a raw pointer ptr.


Overload 3:

A Ptr that takes ownership over a raw pointer ptr.


Overload 4:

A Ptr that takes ownership over a raw pointer ptr.


Overload 5:

A Ptr that takes ownership over a raw pointer ptr.


Overload 6:

A Ptr that takes ownership over a raw pointer ptr.


Overload 7:

A Ptr that takes ownership over a raw pointer ptr.


Overload 8:

A Ptr that takes ownership over a raw pointer ptr.


Overload 9:

A Ptr that takes ownership over a raw pointer ptr.


Overload 10:

A Ptr that takes ownership over a raw pointer ptr.


Overload 11:

A Ptr that takes ownership over a raw pointer ptr.


Overload 12:

A Ptr that takes ownership over a raw pointer ptr.


Overload 13:

A Ptr that takes ownership over a raw pointer ptr.


Overload 14:

A Ptr that takes ownership over a raw pointer ptr.


Overload 15:

A Ptr that takes ownership over a raw pointer ptr.


Overload 16:

A Ptr that takes ownership over a raw pointer ptr.


Overload 17:

A Ptr that takes ownership over a raw pointer ptr.


Overload 18:

A Ptr that takes ownership over a raw pointer ptr.


Overload 19:

A Ptr that takes ownership over a raw pointer ptr.


Overload 20:

A Ptr that takes ownership over a raw pointer ptr.


Overload 21:

A Ptr that takes ownership over a raw pointer ptr.


Overload 22:

A Ptr that takes ownership over a raw pointer ptr.


Overload 23:

A Ptr that takes ownership over a raw pointer ptr.


Overload 24:

A Ptr that takes ownership over a raw pointer ptr.


Overload 25:

A Ptr that takes ownership over a raw pointer ptr.


Overload 26:

A Ptr that takes ownership over a raw pointer ptr.


Overload 27:

A Ptr that takes ownership over a raw pointer ptr.


Overload 28:

A Ptr that takes ownership over a raw pointer ptr.


Overload 29:

A Ptr that takes ownership over a raw pointer ptr.


Overload 30:

A Ptr that takes ownership over a raw pointer ptr.


Overload 31:

A Ptr that takes ownership over a raw pointer ptr.


Overload 32:

A Ptr that takes ownership over a raw pointer ptr.


Overload 33:

A Ptr that takes ownership over a raw pointer ptr.


Overload 34:

A Ptr that takes ownership over a raw pointer ptr.


Overload 35:

A Ptr that takes ownership over a raw pointer ptr.


Overload 36:

A Ptr that takes ownership over a raw pointer ptr.


Overload 37:

A Ptr that takes ownership over a raw pointer ptr.


Overload 38:

A Ptr that takes ownership over a raw pointer ptr.


Overload 39:

A Ptr that takes ownership over a raw pointer ptr.


Overload 40:

A Ptr that takes ownership over a raw pointer ptr.


Overload 41:

A Ptr that takes ownership over a raw pointer ptr.


Overload 42:

A Ptr that takes ownership over a raw pointer ptr.


Overload 43:

A Ptr that takes ownership over a raw pointer ptr.


Overload 44:

A Ptr that takes ownership over a raw pointer ptr.


Overload 45:

A Ptr that takes ownership over a raw pointer ptr.


Overload 46:

A Ptr that takes ownership over a raw pointer ptr.


Overload 47:

A Ptr that takes ownership over a raw pointer ptr.


Overload 48:

A Ptr that takes ownership over a raw pointer ptr.


Overload 49:

A Ptr that takes ownership over a raw pointer ptr.


Overload 50:

A Ptr that takes ownership over a raw pointer ptr.


Overload 51:

A Ptr that takes ownership over a raw pointer ptr.


Overload 52:

A Ptr that takes ownership over a raw pointer ptr.


Overload 53:

A Ptr that takes ownership over a raw pointer ptr.


Overload 54:

A Ptr that takes ownership over a raw pointer ptr.


Overload 55:

A Ptr that takes ownership over a raw pointer ptr.


Overload 56:

A Ptr that takes ownership over a raw pointer ptr.


Overload 57:

A Ptr that takes ownership over a raw pointer ptr.


Overload 58:

A Ptr that takes ownership over a raw pointer ptr.


Overload 59:

A Ptr that takes ownership over a raw pointer ptr.


Overload 60:

A Ptr that takes ownership over a raw pointer ptr.


Overload 61:

A Ptr that takes ownership over a raw pointer ptr.


Overload 62:

A Ptr that takes ownership over a raw pointer ptr.


Overload 63:

A Ptr that takes ownership over a raw pointer ptr.


Overload 64:

A Ptr that takes ownership over a raw pointer ptr.


Overload 65:

A Ptr that takes ownership over a raw pointer ptr.


Overload 66:

A Ptr that takes ownership over a raw pointer ptr.


Overload 67:

A Ptr that takes ownership over a raw pointer ptr.


Overload 68:

A Ptr that takes ownership over a raw pointer ptr.


Overload 69:

A Ptr that takes ownership over a raw pointer ptr.


Overload 70:

A Ptr that takes ownership over a raw pointer ptr.


Overload 71:

A Ptr that takes ownership over a raw pointer ptr.


Overload 72:

A Ptr that takes ownership over a raw pointer ptr.


Overload 73:

A Ptr that takes ownership over a raw pointer ptr.


Overload 74:

A Ptr that takes ownership over a raw pointer ptr.


Overload 75:

A Ptr that takes ownership over a raw pointer ptr.


Overload 76:

A Ptr that takes ownership over a raw pointer ptr.


Overload 77:

A Ptr that takes ownership over a raw pointer ptr.


Overload 78:

A Ptr that takes ownership over a raw pointer ptr.


Overload 79:

A Ptr that takes ownership over a raw pointer ptr.


Overload 80:

A Ptr that takes ownership over a raw pointer ptr.


Overload 81:

A Ptr that takes ownership over a raw pointer ptr.


Overload 82:

A Ptr that takes ownership over a raw pointer ptr.


Overload 83:

A Ptr that takes ownership over a raw pointer ptr.


Overload 84:

A Ptr that takes ownership over a raw pointer ptr.


Overload 85:

A Ptr that takes ownership over a raw pointer ptr.


Overload 86:

A Ptr that takes ownership over a raw pointer ptr.


Overload 87:

A Ptr that takes ownership over a raw pointer ptr.


Overload 88:

A Ptr that takes ownership over a raw pointer ptr.


Overload 89:

A Ptr that takes ownership over a raw pointer ptr.


Overload 90:

A Ptr that takes ownership over a raw pointer ptr.


Overload 91:

A Ptr that takes ownership over a raw pointer ptr.


Overload 92:

A Ptr that takes ownership over a raw pointer ptr.


Overload 93:

A Ptr that takes ownership over a raw pointer ptr.


Overload 94:

A Ptr that takes ownership over a raw pointer ptr.


Overload 95:

A Ptr that takes ownership over a raw pointer ptr.


Overload 96:

A Ptr that takes ownership over a raw pointer ptr.


Overload 97:

A Ptr that takes ownership over a raw pointer ptr.


Overload 98:

A Ptr that takes ownership over a raw pointer ptr.


Overload 99:

A Ptr that takes ownership over a raw pointer ptr.


Overload 100:

A Ptr that takes ownership over a raw pointer ptr.


Overload 101:

A Ptr that takes ownership over a raw pointer ptr.


Overload 102:

A Ptr that takes ownership over a raw pointer ptr.


Overload 103:

A Ptr that takes ownership over a raw pointer ptr.


Overload 104:

A Ptr that takes ownership over a raw pointer ptr.


Overload 105:

A Ptr that takes ownership over a raw pointer ptr.


Overload 106:

A Ptr that takes ownership over a raw pointer ptr.


Overload 107:

A Ptr that takes ownership over a raw pointer ptr.


Overload 108:

A Ptr that takes ownership over a raw pointer ptr.


Overload 109:

A Ptr that takes ownership over a raw pointer ptr.


Overload 110:

A Ptr that takes ownership over a raw pointer ptr.


Overload 111:

A Ptr that takes ownership over a raw pointer ptr.


Overload 112:

A Ptr that takes ownership over a raw pointer ptr.


Overload 113:

A Ptr that takes ownership over a raw pointer ptr.


Overload 114:

A Ptr that takes ownership over a raw pointer ptr.


Overload 115:

A Ptr that takes ownership over a raw pointer ptr.


Overload 116:

A Ptr that takes ownership over a raw pointer ptr.


Overload 117:

A Ptr that takes ownership over a raw pointer ptr.


Overload 118:

A Ptr that takes ownership over a raw pointer ptr.


Overload 119:

A Ptr that takes ownership over a raw pointer ptr.


Overload 120:

A Ptr that takes ownership over a raw pointer ptr.


Overload 121:

A Ptr that takes ownership over a raw pointer ptr.


Overload 122:

A Ptr that takes ownership over a raw pointer ptr.


Overload 123:

A Ptr that takes ownership over a raw pointer ptr.


Overload 124:

A Ptr that takes ownership over a raw pointer ptr.


Overload 125:

A Ptr that takes ownership over a raw pointer ptr.


Overload 126:

A Ptr that takes ownership over a raw pointer ptr.


Overload 127:

A Ptr that takes ownership over a raw pointer ptr.


Overload 128:

A Ptr that takes ownership over a raw pointer ptr.


Overload 129:

A Ptr that takes ownership over a raw pointer ptr.


Overload 130:

A Ptr that takes ownership over a raw pointer ptr.


Overload 131:

A Ptr that takes ownership over a raw pointer ptr.


Overload 132:

A Ptr that takes ownership over a raw pointer ptr.


Overload 133:

A Ptr that takes ownership over a raw pointer ptr.


Overload 134:

A Ptr that takes ownership over a raw pointer ptr.


Overload 135:

A Ptr that takes ownership over a raw pointer ptr.


Overload 136:

A Ptr that takes ownership over a raw pointer ptr.


Overload 137:

A Ptr that takes ownership over a raw pointer ptr.


Overload 138:

A Ptr that takes ownership over a raw pointer ptr.


Overload 139:

A Ptr that takes ownership over a raw pointer ptr.


Overload 140:

A Ptr that takes ownership over a raw pointer ptr.


Overload 141:

A Ptr that takes ownership over a raw pointer ptr.


Overload 142:

A Ptr that takes ownership over a raw pointer ptr.


Overload 143:

A Ptr that takes ownership over a raw pointer ptr.


Overload 144:

A Ptr that takes ownership over a raw pointer ptr.


Overload 145:

A Ptr that takes ownership over a raw pointer ptr.


Overload 146:

A Ptr that takes ownership over a raw pointer ptr.


Overload 147:

A Ptr that takes ownership over a raw pointer ptr.


Overload 148:

A Ptr that takes ownership over a raw pointer ptr.


Overload 149:

A Ptr that takes ownership over a raw pointer ptr.


Overload 150:

A Ptr that takes ownership over a raw pointer ptr.


Overload 151:

A Ptr that takes ownership over a raw pointer ptr.


Overload 152:

A Ptr that takes ownership over a raw pointer ptr.


Overload 153:

A Ptr that takes ownership over a raw pointer ptr.


Overload 154:

A Ptr that takes ownership over a raw pointer ptr.


Overload 155:

A Ptr that takes ownership over a raw pointer ptr.


Overload 156:

A Ptr that takes ownership over a raw pointer ptr.


Overload 157:

A Ptr that takes ownership over a raw pointer ptr.


Overload 158:

A Ptr that takes ownership over a raw pointer ptr.


Overload 159:

A Ptr that takes ownership over a raw pointer ptr.


Overload 160:

A Ptr that takes ownership over a raw pointer ptr.


Overload 161:

A Ptr that takes ownership over a raw pointer ptr.


Overload 162:

A Ptr that takes ownership over a raw pointer ptr.


Overload 163:

A Ptr that takes ownership over a raw pointer ptr.


Overload 164:

A Ptr that takes ownership over a raw pointer ptr.


Overload 165:

A Ptr that takes ownership over a raw pointer ptr.


Overload 166:

A Ptr that takes ownership over a raw pointer ptr.


Overload 167:

A Ptr that takes ownership over a raw pointer ptr.


Overload 168:

A Ptr that takes ownership over a raw pointer ptr.


Overload 169:

A Ptr that takes ownership over a raw pointer ptr.


Overload 170:

A Ptr that takes ownership over a raw pointer ptr.


Overload 171:

A Ptr that takes ownership over a raw pointer ptr.


Overload 172:

A Ptr that takes ownership over a raw pointer ptr.


Overload 173:

A Ptr that takes ownership over a raw pointer ptr.


Overload 174:

A Ptr that takes ownership over a raw pointer ptr.


Overload 175:

A Ptr that takes ownership over a raw pointer ptr.


Overload 176:

A Ptr that takes ownership over a raw pointer ptr.


Overload 177:

A Ptr that takes ownership over a raw pointer ptr.


Overload 178:

A Ptr that takes ownership over a raw pointer ptr.


Overload 179:

A Ptr that takes ownership over a raw pointer ptr.


Overload 180:

A Ptr that takes ownership over a raw pointer ptr.


Overload 181:

A Ptr that takes ownership over a raw pointer ptr.


Overload 182:

A Ptr that takes ownership over a raw pointer ptr.


Overload 183:

A Ptr that takes ownership over a raw pointer ptr.


Overload 184:

A Ptr that takes ownership over a raw pointer ptr.


Overload 185:

A Ptr that takes ownership over a raw pointer ptr.


Overload 186:

A Ptr that takes ownership over a raw pointer ptr.


Overload 187:

A Ptr that takes ownership over a raw pointer ptr.


Overload 188:

A Ptr that takes ownership over a raw pointer ptr.


Overload 189:

A Ptr that takes ownership over a raw pointer ptr.


Overload 190:

A Ptr that takes ownership over a raw pointer ptr.


Overload 191:

A Ptr that takes ownership over a raw pointer ptr.


Overload 192:

A Ptr that takes ownership over a raw pointer ptr.


Overload 193:

A Ptr that takes ownership over a raw pointer ptr.


Overload 194:

A Ptr that takes ownership over a raw pointer ptr.


Overload 195:

A Ptr that takes ownership over a raw pointer ptr.


Overload 196:

A Ptr that takes ownership over a raw pointer ptr.


Overload 197:

A Ptr that takes ownership over a raw pointer ptr.


Overload 198:

A Ptr that takes ownership over a raw pointer ptr.


Overload 199:

A Ptr that takes ownership over a raw pointer ptr.


Overload 200:

A Ptr that takes ownership over a raw pointer ptr.


Overload 201:

A Ptr that takes ownership over a raw pointer ptr.


Overload 202:

A Ptr that takes ownership over a raw pointer ptr.


Overload 203:

A Ptr that takes ownership over a raw pointer ptr.


Overload 204:

A Ptr that takes ownership over a raw pointer ptr.


Overload 205:

A Ptr that takes ownership over a raw pointer ptr.


Overload 206:

A Ptr that takes ownership over a raw pointer ptr.


Overload 207:

A Ptr that takes ownership over a raw pointer ptr.


Overload 208:

A Ptr that takes ownership over a raw pointer ptr.


Overload 209:

A Ptr that takes ownership over a raw pointer ptr.


Overload 210:

A Ptr that takes ownership over a raw pointer ptr.


Overload 211:

A Ptr that takes ownership over a raw pointer ptr.


Overload 212:

A Ptr that takes ownership over a raw pointer ptr.


Overload 213:

A Ptr that takes ownership over a raw pointer ptr.


Overload 214:

A Ptr that takes ownership over a raw pointer ptr.


Overload 215:

A Ptr that takes ownership over a raw pointer ptr.


Overload 216:

A Ptr that takes ownership over a raw pointer ptr.


Overload 217:

A Ptr that takes ownership over a raw pointer ptr.


Overload 218:

A Ptr that takes ownership over a raw pointer ptr.


Overload 219:

A Ptr that takes ownership over a raw pointer ptr.


Overload 220:

A Ptr that takes ownership over a raw pointer ptr.


Overload 221:

A Ptr that takes ownership over a raw pointer ptr.


Overload 222:

A Ptr that takes ownership over a raw pointer ptr.


Overload 223:

A Ptr that takes ownership over a raw pointer ptr.


Overload 224:

A Ptr that takes ownership over a raw pointer ptr.


Overload 225:

A Ptr that takes ownership over a raw pointer ptr.


Overload 226:

A Ptr that takes ownership over a raw pointer ptr.


Overload 227:

A Ptr that takes ownership over a raw pointer ptr.


Overload 228:

A Ptr that takes ownership over a raw pointer ptr.


Overload 229:

A Ptr that takes ownership over a raw pointer ptr.


Overload 230:

A Ptr that takes ownership over a raw pointer ptr.


Overload 231:

A Ptr that takes ownership over a raw pointer ptr.


Overload 232:

A Ptr that takes ownership over a raw pointer ptr.


Overload 233:

A Ptr that takes ownership over a raw pointer ptr.


Overload 234:

A Ptr that takes ownership over a raw pointer ptr.


Overload 235:

A Ptr that takes ownership over a raw pointer ptr.


Overload 236:

A Ptr that takes ownership over a raw pointer ptr.


Overload 237:

A Ptr that takes ownership over a raw pointer ptr.


Overload 238:

A Ptr that takes ownership over a raw pointer ptr.


Overload 239:

A Ptr that takes ownership over a raw pointer ptr.


Overload 240:

A Ptr that takes ownership over a raw pointer ptr.


Overload 241:

A Ptr that takes ownership over a raw pointer ptr.


Overload 242:

A Ptr that takes ownership over a raw pointer ptr.


Overload 243:

A Ptr that takes ownership over a raw pointer ptr.


Overload 244:

A Ptr that takes ownership over a raw pointer ptr.


Overload 245:

A Ptr that takes ownership over a raw pointer ptr.


Overload 246:

A Ptr that takes ownership over a raw pointer ptr.


Overload 247:

A Ptr that takes ownership over a raw pointer ptr.


Overload 248:

A Ptr that takes ownership over a raw pointer ptr.


Overload 249:

A Ptr that takes ownership over a raw pointer ptr.


Overload 250:

A Ptr that takes ownership over a raw pointer ptr.


Overload 251:

A Ptr that takes ownership over a raw pointer ptr.


Overload 252:

A Ptr that takes ownership over a raw pointer ptr.


Overload 253:

A Ptr that takes ownership over a raw pointer ptr.


Overload 254:

A Ptr that takes ownership over a raw pointer ptr.


Overload 255:

A Ptr that takes ownership over a raw pointer ptr.


Overload 256:

A Ptr that takes ownership over a raw pointer ptr.


Overload 257:

A Ptr that takes ownership over a raw pointer ptr.


Overload 258:

A Ptr that takes ownership over a raw pointer ptr.


Overload 259:

A Ptr that takes ownership over a raw pointer ptr.


Overload 260:

A Ptr that takes ownership over a raw pointer ptr.


Overload 261:

A Ptr that takes ownership over a raw pointer ptr.


Overload 262:

A Ptr that takes ownership over a raw pointer ptr.


Overload 263:

A Ptr that takes ownership over a raw pointer ptr.


Overload 264:

A Ptr that takes ownership over a raw pointer ptr.


Overload 265:

A Ptr that takes ownership over a raw pointer ptr.


Overload 266:

A Ptr that takes ownership over a raw pointer ptr.


Overload 267:

A Ptr that takes ownership over a raw pointer ptr.


Overload 268:

A Ptr that takes ownership over a raw pointer ptr.


Overload 269:

A Ptr that takes ownership over a raw pointer ptr.


Overload 270:

A Ptr that takes ownership over a raw pointer ptr.


Overload 271:

A Ptr that takes ownership over a raw pointer ptr.


Overload 272:

A Ptr that takes ownership over a raw pointer ptr.


Overload 273:

A Ptr that takes ownership over a raw pointer ptr.


Overload 274:

A Ptr that takes ownership over a raw pointer ptr.


Overload 275:

A Ptr that takes ownership over a raw pointer ptr.


Overload 276:

A Ptr that takes ownership over a raw pointer ptr.


Overload 277:

A Ptr that takes ownership over a raw pointer ptr.


Overload 278:

A Ptr that takes ownership over a raw pointer ptr.


Overload 279:

A Ptr that takes ownership over a raw pointer ptr.


Overload 280:

A Ptr that takes ownership over a raw pointer ptr.


Overload 281:

A Ptr that takes ownership over a raw pointer ptr.


Overload 282:

A Ptr that takes ownership over a raw pointer ptr.


Overload 283:

A Ptr that takes ownership over a raw pointer ptr.


Overload 284:

A Ptr that takes ownership over a raw pointer ptr.


Overload 285:

A Ptr that takes ownership over a raw pointer ptr.


Overload 286:

A Ptr that takes ownership over a raw pointer ptr.


Overload 287:

A Ptr that takes ownership over a raw pointer ptr.


Overload 288:

A Ptr that takes ownership over a raw pointer ptr.


Overload 289:

A Ptr that takes ownership over a raw pointer ptr.


Overload 290:

A Ptr that takes ownership over a raw pointer ptr.


Overload 291:

A Ptr that takes ownership over a raw pointer ptr.


Overload 292:

A Ptr that takes ownership over a raw pointer ptr.


Overload 293:

A Ptr that takes ownership over a raw pointer ptr.


Overload 294:

A Ptr that takes ownership over a raw pointer ptr.


Overload 295:

A Ptr that takes ownership over a raw pointer ptr.


Overload 296:

A Ptr that takes ownership over a raw pointer ptr.


Overload 297:

A Ptr that takes ownership over a raw pointer ptr.


Overload 298:

A Ptr that takes ownership over a raw pointer ptr.


Overload 299:

A Ptr that takes ownership over a raw pointer ptr.


Overload 300:

A Ptr that takes ownership over a raw pointer ptr.


Overload 301:

A Ptr that takes ownership over a raw pointer ptr.


Overload 302:

A Ptr that takes ownership over a raw pointer ptr.


Overload 303:

A Ptr that takes ownership over a raw pointer ptr.


Overload 304:

A Ptr that takes ownership over a raw pointer ptr.


Overload 305:

A Ptr that takes ownership over a raw pointer ptr.


Overload 306:

A Ptr that takes ownership over a raw pointer ptr.


Overload 307:

A Ptr that takes ownership over a raw pointer ptr.


Overload 308:

A Ptr that takes ownership over a raw pointer ptr.


Overload 309:

A Ptr that takes ownership over a raw pointer ptr.


Overload 310:

A Ptr that takes ownership over a raw pointer ptr.


Overload 311:

A Ptr that takes ownership over a raw pointer ptr.


Overload 312:

A Ptr that takes ownership over a raw pointer ptr.


Overload 313:

A Ptr that takes ownership over a raw pointer ptr.


Overload 314:

A Ptr that takes ownership over a raw pointer ptr.


Overload 315:

A Ptr that takes ownership over a raw pointer ptr.


Overload 316:

A Ptr that takes ownership over a raw pointer ptr.


Overload 317:

A Ptr that takes ownership over a raw pointer ptr.


Overload 318:

A Ptr that takes ownership over a raw pointer ptr.


Overload 319:

A Ptr that takes ownership over a raw pointer ptr.


Overload 320:

A Ptr that takes ownership over a raw pointer ptr.


Overload 321:

A Ptr that takes ownership over a raw pointer ptr.


Overload 322:

A Ptr that takes ownership over a raw pointer ptr.