sdurw_pathplanners module¶
-
class
sdurw_pathplanners.
ARWExpand
(*args, **kwargs)¶ Bases:
object
ARWExpand expands a random walk in the configuration space by one step.
-
duplicate
(start)¶ Construct a new random walk with start node at start.
-
expand
()¶ Expand the path by one step and return true if a new configuration was added to the path.
The current path can be retrieved with ARWExpand::getPath().
- Return type
boolean
- Returns
True iff a node was added to the end of the path.
-
getPath
()¶ The current path of the random walk.
-
static
make
(*args)¶ Constructor
The expansion method computes the variance for the latest historySize elements of the path and performs one step sampled from a Gaussian distribution with the computed variances. Variances lower than minVariances are never used.
If minVariances is empty, then a default value is chosen based on bounds.
If historySize is negative, a default value is chosen.
- Parameters
bounds (std::pair< Q,Q >) – [in] Configuration space bounds.
constraint (PlannerConstraint) – [in] Path planning constraint.
minVariances (Q) – [in] Minimum variances.
historySize (int) – [in] Number of previous elements of the path to use for variance computation.
-
property
thisown
¶ The membership flag
-
-
class
sdurw_pathplanners.
ARWExpandPtr
(*args)¶ Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
-
deref
()¶ The pointer stored in the object.
-
duplicate
(start)¶ Construct a new random walk with start node at start.
-
expand
()¶ Expand the path by one step and return true if a new configuration was added to the path.
The current path can be retrieved with ARWExpand::getPath().
- Return type
boolean
- Returns
True iff a node was added to the end of the path.
-
getDeref
()¶ Member access operator.
-
getPath
()¶ The current path of the random walk.
-
isNull
()¶ checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null
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)¶ Constructor
The expansion method computes the variance for the latest historySize elements of the path and performs one step sampled from a Gaussian distribution with the computed variances. Variances lower than minVariances are never used.
If minVariances is empty, then a default value is chosen based on bounds.
If historySize is negative, a default value is chosen.
- Parameters
bounds (std::pair< Q,Q >) – [in] Configuration space bounds.
constraint (PlannerConstraint) – [in] Path planning constraint.
minVariances (Q) – [in] Minimum variances.
historySize (int) – [in] Number of previous elements of the path to use for variance computation.
-
property
thisown
¶ The membership flag
-
-
sdurw_pathplanners.
ARWExpand_make
(*args)¶ Constructor
The expansion method computes the variance for the latest historySize elements of the path and performs one step sampled from a Gaussian distribution with the computed variances. Variances lower than minVariances are never used.
If minVariances is empty, then a default value is chosen based on bounds.
If historySize is negative, a default value is chosen.
- Parameters
bounds (std::pair< Q,Q >) – [in] Configuration space bounds.
constraint (PlannerConstraint) – [in] Path planning constraint.
minVariances (Q) – [in] Minimum variances.
historySize (int) – [in] Number of previous elements of the path to use for variance computation.
-
class
sdurw_pathplanners.
ARWPlanner
(*args, **kwargs)¶ Bases:
object
Adaptive Random Walk planners
The ARW planners are based on the algorithm of: Stefano Carpin and Gianluigi Pillonetto, Motion Planning Using Adaptive Random Walks, IEEE Transactions on Robotics, Vol. 21, No. 1, 2005.
-
static
makeQToQPlanner
(*args)¶ Overload 1:
ARW based point-to-point planner.
The ARW planner expands its paths using instances of expand. If the end point of one of the paths is within a distance nearDistance from a goal node when measured with metric, then that connection is verified. If that connection is valid, the full path is returned.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
expand (rw::core::Ptr< ARWExpand >) – [in] ARW expansion strategy.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Distance to goal node measure.
nearDistance (float) – [in] Threshold for distance to goal node.
Overload 2:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance (float) – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize (int) – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
Overload 3:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance (float) – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
Overload 4:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
Overload 5:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
-
property
thisown
¶ The membership flag
-
static
-
class
sdurw_pathplanners.
ARWPlannerPtr
(*args)¶ Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
-
deref
()¶ The pointer stored in the object.
-
getDeref
()¶ Member access operator.
-
isNull
()¶ checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null
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.
-
makeQToQPlanner
(*args)¶ Overload 1:
ARW based point-to-point planner.
The ARW planner expands its paths using instances of expand. If the end point of one of the paths is within a distance nearDistance from a goal node when measured with metric, then that connection is verified. If that connection is valid, the full path is returned.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
expand (rw::core::Ptr< ARWExpand >) – [in] ARW expansion strategy.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Distance to goal node measure.
nearDistance (float) – [in] Threshold for distance to goal node.
Overload 2:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance (float) – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize (int) – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
Overload 3:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance (float) – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
Overload 4:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
Overload 5:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
-
property
thisown
¶ The membership flag
-
-
sdurw_pathplanners.
ARWPlanner_makeQToQPlanner
(*args)¶ Overload 1:
ARW based point-to-point planner.
The ARW planner expands its paths using instances of expand. If the end point of one of the paths is within a distance nearDistance from a goal node when measured with metric, then that connection is verified. If that connection is valid, the full path is returned.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
expand (rw::core::Ptr< ARWExpand >) – [in] ARW expansion strategy.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Distance to goal node measure.
nearDistance (float) – [in] Threshold for distance to goal node.
Overload 2:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance (float) – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize (int) – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
Overload 3:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance (float) – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
Overload 4:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
Overload 5:
ARW based point-to-point planner.
Based on device, a default distance metric and expansion strategy is chosen. A connection to a goal node is attempted if the distance is below nearDistance. A variance based expansion method is chosen with variances being calculated for the latest historySize samples.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
metric – [in] Configuration space distance metric. If metric is NULL, a default metric for device is chosen.
nearDistance – [in] Try to connect to the goal if the distance to the goal measured by metric is below this threshold. If metric is null, a default value for nearDistance is chosen.
historySize – [in] Number of previous configurations on the path to include in computation of the next expand step. If historySize is negative, a default value for the parameter is chosen.
-
class
sdurw_pathplanners.
PRMPlanner
(*args)¶ Bases:
object
Implements a probabilistic roadmap (PRM) planner.
The PRMPlanner is implemented freely after [1], and has a number of options:
Lazy Collision Checking: Using lazy collision checking as in [2], the planner can be used for single as well as multiple queries.
Nearest Neighbor Search: The algorithm can either use a partial index table [3] or a simple brute force method to do the nearest neighbor search.
Shortest Path Algorithm: Using the Boost Graph Library, both A* and Dijkstra’s Algorithm may be used for finding the shortest path.
As default the algorithm runs with lazy collision checking, brute force neighbor search and with A* for shortest path search.
As metric the PRMPlanner uses a WeightedEuclideanMetric for which it estimates the weights such that it provides a worst-case estimate of the Cartesian motion of the robots given a change in the configuration.
Example of use
PRMPlanner* prm = new PRMPlanner(device, workcell, state, collisionDetector, resolution); prm-setCollisionCheckingStrategy(PRMPlanner::LAZY); prm-setNeighSearchStrategy(PRMPlanner::BRUTE_FORCE); prm-setShortestPathSearchStrategy(PRMPlanner::A_STAR); prm-buildRoadmap(1000); Path path; bool pathFound = prm-query(qstart, qgoal, path, maxtime);
- [1]: Probabilistic Roadmaps for Path Planning in High-Dimensional
Configuration Spaces, L.E. Kavraki, P. Svestka, J-C. Latombe, M.H. Overmars. IEEE Transactions on Robotics and Automation, Vol. 12, pages 566-580, 1996
- [2]: Path Planning using Lazy PRM, R. Bohlin, L.E. Kavraki. Proceedings
of the IEEE International Conference on Robotics and Automation, Vol. 1, pages 521-528, 2000
- [3]: On Delaying Collision Checking in PRM Planning - Application to
Multi-Robot Coordination, G. Sanchez, J.C. Latombe. The International Journal of Robotics Research, Vol. 21, No. 1, pages 5-26, 2002
-
A_STAR
= 0¶ Use A* to search for shortest path.
-
BRUTE_FORCE
= 0¶ Run through all node and look a which a sufficient close.
-
DIJKSTRA
= 1¶ Use Dijkstra to search for shortest path.
-
FULL
= 2¶ Perform a full check of both nodes and edges.
-
KDTREE
= 2¶ Use KD tree for neighbor search
-
LAZY
= 0¶ Perform a Lazy collision checking (no checking on construction).
-
NODECHECK
= 1¶ Only check node on construction, leave edges unchecked.
-
PARTIAL_INDEX_TABLE
= 1¶ Use a partial index table to make an more efficient lookup.
-
buildRoadmap
(nodecount)¶ Build the roadmap with the setup specified
- Parameters
nodecount (int) – [in] Number of nodes to insert
-
printTimeStats
()¶ print timing stats from previous run.
-
setAStarTimeOutTime
(timeout)¶ Sets the max time of A* before terminating and calling dijkstra
The A* implementation in the boost graph library has a reported bug, which on some platforms in rare occasions may cause it to loop infinitely. If A* uses more than this specified time it will break off and call dijkstra instead.
Default value for this timeout is 1second.
- Parameters
timeout (float) – [in] Timeout time.
-
setCollisionCheckingStrategy
(collisionCheckingStrategy)¶ Sets up the collision checking strategy
Note: Do not call this after the buildRoadmap as it may result in paths with collisions
- Parameters
collisionCheckingStrategy (int) – [in] The collision checking strategy
-
setNeighSearchStrategy
(neighborSearchStrategy)¶ Sets up the nearest neighbor search strategy
- Parameters
neighborSearchStrategy (int) – [in] The nearest neighbor search strategy
-
setNeighborCount
(n)¶ Sets the desired average number of neighbors. Default value is 20.
- Parameters
n (int) – [in] Desired average number of neighbors
-
setPartialIndexTableDimensions
(dimensions)¶ Sets up the number of dimensions for the partial index table
This setting only applies when using the PARTIAL_INDEX_TABLE strategy for nearest neighbor search.
dimensions should be within [1; _device->getDOF()]. The optimal value of dimensions is a tradeoff between memory usage and time. Selecting a value too high compared to the number of nodes in the roadmap may introduce an increase in time due to additional bookkeeping.
The default value is set to 4, which is found suitable for most devices with 6 or 7 degrees of freedom.
- Parameters
dimensions (int) – [in] Number of dimensions, which should be
-
setShortestPathSearchStrategy
(shortestPathSearchStrategy)¶ Sets up the shortest path search strategy
Generally A* is the fastest algorithm, but given a small roadmap Dijkstra may perform better.
- Parameters
shortestPathSearchStrategy (int) – [in] shortestPathSearchStrategy
-
property
thisown
¶ The membership flag
-
class
sdurw_pathplanners.
PRMPlannerPtr
(*args)¶ Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
-
buildRoadmap
(nodecount)¶ Build the roadmap with the setup specified
- Parameters
nodecount (int) – [in] Number of nodes to insert
-
deref
()¶ The pointer stored in the object.
-
getDeref
()¶ Member access operator.
-
isNull
()¶ checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null
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.
-
printTimeStats
()¶ print timing stats from previous run.
-
setAStarTimeOutTime
(timeout)¶ Sets the max time of A* before terminating and calling dijkstra
The A* implementation in the boost graph library has a reported bug, which on some platforms in rare occasions may cause it to loop infinitely. If A* uses more than this specified time it will break off and call dijkstra instead.
Default value for this timeout is 1second.
- Parameters
timeout (float) – [in] Timeout time.
-
setCollisionCheckingStrategy
(collisionCheckingStrategy)¶ Sets up the collision checking strategy
Note: Do not call this after the buildRoadmap as it may result in paths with collisions
- Parameters
collisionCheckingStrategy (int) – [in] The collision checking strategy
-
setNeighSearchStrategy
(neighborSearchStrategy)¶ Sets up the nearest neighbor search strategy
- Parameters
neighborSearchStrategy (int) – [in] The nearest neighbor search strategy
-
setNeighborCount
(n)¶ Sets the desired average number of neighbors. Default value is 20.
- Parameters
n (int) – [in] Desired average number of neighbors
-
setPartialIndexTableDimensions
(dimensions)¶ Sets up the number of dimensions for the partial index table
This setting only applies when using the PARTIAL_INDEX_TABLE strategy for nearest neighbor search.
dimensions should be within [1; _device->getDOF()]. The optimal value of dimensions is a tradeoff between memory usage and time. Selecting a value too high compared to the number of nodes in the roadmap may introduce an increase in time due to additional bookkeeping.
The default value is set to 4, which is found suitable for most devices with 6 or 7 degrees of freedom.
- Parameters
dimensions (int) – [in] Number of dimensions, which should be
-
setShortestPathSearchStrategy
(shortestPathSearchStrategy)¶ Sets up the shortest path search strategy
Generally A* is the fastest algorithm, but given a small roadmap Dijkstra may perform better.
- Parameters
shortestPathSearchStrategy (int) – [in] shortestPathSearchStrategy
-
property
thisown
¶ The membership flag
-
-
class
sdurw_pathplanners.
RRTPlanner
(*args, **kwargs)¶ Bases:
object
RRT based planners
-
RRTBalancedBidirectional
= 3¶ Balanced, bidirectional RRT.
The algorithm of the planner is in the style of RDT_BALANCED_BIDIRECTIONAL(), page 195 of Steven M. Lavalle, “Planning Algorithms”, 2006.
-
RRTBasic
= 0¶ Simple non-greedy, bidirectional RRT.
See BasicPlanner(), page 109 of James J. Kuffner, “Autonomous Agensts for Real-Time Animation”, 1999.
-
RRTBidirectional
= 2¶ Bidirectional RRT.
The algorithm of the planner is in the style of RDT_BALANCED_BIDIRECTIONAL(), page 195 of Steven M. Lavalle, “Planning Algorithms”, 2006, except this planner is the non-balanced version.
-
RRTConnect
= 1¶ RRT-Connect planner.
See James J. Kuffner and Steven M. LaValle, “RRT-Connect: An Efficient Approach to Single-Query Path Planning”, ICRA, 2000.
-
static
makeQToQPlanner
(*args)¶ Overload 1:
RRT based point-to-point planner.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
sampler (rw::core::Ptr< QSampler >) – [in] Sampler of the configuration space.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Metric for nearest neighbor search.
extend (float) – [in] Distance measured by metric by which to extend the tree towards an attractor configuration.
type (int) – [in] The particular variation the RRT planner algorithm.
Overload 2:
RRT based point-to-point planner.
Default configuration space sampling strategy (rw::pathplanning::QSampler) and distance metrics (rw:math::QMetric) are chosen based on device.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
type (int) – [in] The particular variation the RRT planner algorithm.
Overload 3:
RRT based point-to-point planner.
Default configuration space sampling strategy (rw::pathplanning::QSampler) and distance metrics (rw:math::QMetric) are chosen based on device.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
type – [in] The particular variation the RRT planner algorithm.
-
property
thisown
¶ The membership flag
-
-
class
sdurw_pathplanners.
RRTPlannerPtr
(*args)¶ Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
-
deref
()¶ The pointer stored in the object.
-
getDeref
()¶ Member access operator.
-
isNull
()¶ checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null
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.
-
makeQToQPlanner
(*args)¶ Overload 1:
RRT based point-to-point planner.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
sampler (rw::core::Ptr< QSampler >) – [in] Sampler of the configuration space.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Metric for nearest neighbor search.
extend (float) – [in] Distance measured by metric by which to extend the tree towards an attractor configuration.
type (int) – [in] The particular variation the RRT planner algorithm.
Overload 2:
RRT based point-to-point planner.
Default configuration space sampling strategy (rw::pathplanning::QSampler) and distance metrics (rw:math::QMetric) are chosen based on device.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
type (int) – [in] The particular variation the RRT planner algorithm.
Overload 3:
RRT based point-to-point planner.
Default configuration space sampling strategy (rw::pathplanning::QSampler) and distance metrics (rw:math::QMetric) are chosen based on device.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
type – [in] The particular variation the RRT planner algorithm.
-
property
thisown
¶ The membership flag
-
-
sdurw_pathplanners.
RRTPlanner_makeQToQPlanner
(*args)¶ Overload 1:
RRT based point-to-point planner.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
sampler (rw::core::Ptr< QSampler >) – [in] Sampler of the configuration space.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Metric for nearest neighbor search.
extend (float) – [in] Distance measured by metric by which to extend the tree towards an attractor configuration.
type (int) – [in] The particular variation the RRT planner algorithm.
Overload 2:
RRT based point-to-point planner.
Default configuration space sampling strategy (rw::pathplanning::QSampler) and distance metrics (rw:math::QMetric) are chosen based on device.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
type (int) – [in] The particular variation the RRT planner algorithm.
Overload 3:
RRT based point-to-point planner.
Default configuration space sampling strategy (rw::pathplanning::QSampler) and distance metrics (rw:math::QMetric) are chosen based on device.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
type – [in] The particular variation the RRT planner algorithm.
-
class
sdurw_pathplanners.
SBLExpand
(*args, **kwargs)¶ Bases:
object
Interface for sampling a configuration in the vicinity of some other configuration.
SBLExpand is a primitive for planners in the SBL family. The primitive takes a configuration q as parameter and returns another configuration somewhere in the vicinity of q.
Different implementations can have different policies with respect to what constraints are satisfied by the configurations returned.
-
expand
(q)¶ A configuration sampled from the vicinity of q.
Implementation dependant, the sampler may return the empty configuration if no configurations can be sampled near q.
-
static
makeShrinkingUniformBox
(*args)¶ Overload 1:
Sample within a box of decreasing size until a collision free configuration is found.
The inner box shrinks in size as 1, 1/2, 1/3, …
This form of expansion is typical for SBL planners.
The inner and outer box are specified as explained for makeUniformBox().
Overload 2:
Sample within a box of shrinking size until a collision free configuration is found.
The inner box shrinks in size as 1, 1/2, 1/3, …
This form of expansion is typical for SBL planners.
The inner and outer box are specified as explained for makeUniformBox().
-
static
makeShrinkingUniformJacobianBox
(constraint, device, state, jacobian, angle_max=- 1, disp_max=- 1)¶ Sample within a box of shrinking size until a collision free configuration is found.
The size of the inner box depends on the Jacobian of the current configuration. The radius for the i’th dimension of the inner box is
R_i = min(angle_max / angle_vel, disp_max / disp_vel)
where angle_vel is the magnitude of the angular velocity and disp_vel is the magnitude of the translational velocity.
If jacobian is NULL, a default device Jacobian is chosen based on device.
If angle_max or disp_max is negative, a default value for the variable is chosen.
The inner box shrinks in size as 1, 1/2, 1/3, …
-
static
makeUniformBox
(*args)¶ Overload 1:
Expansion within the overlap of an inner and outer box.
Given a configuration q, the expand() method returns a configuration sampled uniformly at random from the intersection between
q + inner
and
outer
Given a device, you typically use device.getBounds() as the box for the outer configuration space.
If the overlap between the boxes is empty, expand() returns the empty configuration.
Overload 2:
Expansion within a scaled down box of the configuration space.
Given a configuration q, the expand() method samples a configuration uniformly at random from the intersection between
q + inner
and
outer
where inner equals outer scaled by a factor of ratio and centered at origo.
This is a form of expansion you will use in a standard implementation of an SBL planner.
ratio must be positive.
If outer is non-empty, the expand() method will always return a non-empty configuration.
-
property
thisown
¶ The membership flag
-
-
class
sdurw_pathplanners.
SBLExpandPtr
(*args)¶ Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
-
deref
()¶ The pointer stored in the object.
-
expand
(q)¶ A configuration sampled from the vicinity of q.
Implementation dependant, the sampler may return the empty configuration if no configurations can be sampled near q.
-
getDeref
()¶ Member access operator.
-
isNull
()¶ checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null
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.
-
makeShrinkingUniformBox
(*args)¶ Overload 1:
Sample within a box of decreasing size until a collision free configuration is found.
The inner box shrinks in size as 1, 1/2, 1/3, …
This form of expansion is typical for SBL planners.
The inner and outer box are specified as explained for makeUniformBox().
Overload 2:
Sample within a box of shrinking size until a collision free configuration is found.
The inner box shrinks in size as 1, 1/2, 1/3, …
This form of expansion is typical for SBL planners.
The inner and outer box are specified as explained for makeUniformBox().
-
makeShrinkingUniformJacobianBox
(constraint, device, state, jacobian, angle_max=- 1, disp_max=- 1)¶ Sample within a box of shrinking size until a collision free configuration is found.
The size of the inner box depends on the Jacobian of the current configuration. The radius for the i’th dimension of the inner box is
R_i = min(angle_max / angle_vel, disp_max / disp_vel)
where angle_vel is the magnitude of the angular velocity and disp_vel is the magnitude of the translational velocity.
If jacobian is NULL, a default device Jacobian is chosen based on device.
If angle_max or disp_max is negative, a default value for the variable is chosen.
The inner box shrinks in size as 1, 1/2, 1/3, …
-
makeUniformBox
(*args)¶ Overload 1:
Expansion within the overlap of an inner and outer box.
Given a configuration q, the expand() method returns a configuration sampled uniformly at random from the intersection between
q + inner
and
outer
Given a device, you typically use device.getBounds() as the box for the outer configuration space.
If the overlap between the boxes is empty, expand() returns the empty configuration.
Overload 2:
Expansion within a scaled down box of the configuration space.
Given a configuration q, the expand() method samples a configuration uniformly at random from the intersection between
q + inner
and
outer
where inner equals outer scaled by a factor of ratio and centered at origo.
This is a form of expansion you will use in a standard implementation of an SBL planner.
ratio must be positive.
If outer is non-empty, the expand() method will always return a non-empty configuration.
-
property
thisown
¶ The membership flag
-
-
sdurw_pathplanners.
SBLExpand_makeShrinkingUniformBox
(*args)¶ Overload 1:
Sample within a box of decreasing size until a collision free configuration is found.
The inner box shrinks in size as 1, 1/2, 1/3, …
This form of expansion is typical for SBL planners.
The inner and outer box are specified as explained for makeUniformBox().
Overload 2:
Sample within a box of shrinking size until a collision free configuration is found.
The inner box shrinks in size as 1, 1/2, 1/3, …
This form of expansion is typical for SBL planners.
The inner and outer box are specified as explained for makeUniformBox().
-
sdurw_pathplanners.
SBLExpand_makeShrinkingUniformJacobianBox
(constraint, device, state, jacobian, angle_max=- 1, disp_max=- 1)¶ Sample within a box of shrinking size until a collision free configuration is found.
The size of the inner box depends on the Jacobian of the current configuration. The radius for the i’th dimension of the inner box is
R_i = min(angle_max / angle_vel, disp_max / disp_vel)
where angle_vel is the magnitude of the angular velocity and disp_vel is the magnitude of the translational velocity.
If jacobian is NULL, a default device Jacobian is chosen based on device.
If angle_max or disp_max is negative, a default value for the variable is chosen.
The inner box shrinks in size as 1, 1/2, 1/3, …
-
sdurw_pathplanners.
SBLExpand_makeUniformBox
(*args)¶ Overload 1:
Expansion within the overlap of an inner and outer box.
Given a configuration q, the expand() method returns a configuration sampled uniformly at random from the intersection between
q + inner
and
outer
Given a device, you typically use device.getBounds() as the box for the outer configuration space.
If the overlap between the boxes is empty, expand() returns the empty configuration.
Overload 2:
Expansion within a scaled down box of the configuration space.
Given a configuration q, the expand() method samples a configuration uniformly at random from the intersection between
q + inner
and
outer
where inner equals outer scaled by a factor of ratio and centered at origo.
This is a form of expansion you will use in a standard implementation of an SBL planner.
ratio must be positive.
If outer is non-empty, the expand() method will always return a non-empty configuration.
-
class
sdurw_pathplanners.
SBLOptions
(constraint, edgeConstraint, expansion, metric, connectRadius)¶ Bases:
object
SBL planner setup.
SBLOptions is the value stored in SBLSetup.
SBLOptions is a seperate file so that we can keep SBLSetup as abstract as possible.
SBLOptions is used by SBLInternal and is for internal use only.
-
ConnectAlways
= 0¶ always connect (default)
-
ConnectAtReset
= 1¶ connect only at reset.
-
LargestTree
= 3¶ choose the largest tree.
-
NearestFromCell
= 2¶ take the nearest node from the cell where node n lies.
-
NearestNode
= 3¶ search for the nearest node (default)
-
SmallestTree
= 2¶ choose the smallest tree.
-
UniformFromCell
= 1¶ take a random node within the cell where node n lies.
-
UniformSelect
= 0¶ take a random node.
-
UniformTree
= 0¶ randomly select one of the two trees (default)
-
WeightedTree
= 1¶ choose the tree randomly, but weighted according to the size of the tree.
-
property
connectAt
¶ (default is ConnectAlways).
-
property
connectRadius
¶ Attempt connection of the trees if the distance to the nearest neighbor is below this threshold.
-
property
constraint
¶ The constraint that determined if a path or configuration is valid (collision free) or not.
-
property
expansion
¶ The expand policy used to sample new configurations in the vicinity.
-
property
metric
¶ the distance metric for nearest neighbor searching.
-
property
nearNodeSelection
¶ (default is NearestNode).
-
property
nodesPerCell
¶ (default is 10).
-
property
resetCount
¶ (default is 20).
-
property
rootSampleInterval
¶ (default is 25).
-
property
thisown
¶ The membership flag
-
property
treeSelection
¶ (default is UniformTree).
-
-
class
sdurw_pathplanners.
SBLPlanner
(*args, **kwargs)¶ Bases:
object
SBL based planners.
-
static
makeQToQPlanner
(setup)¶ An SBL based point-to-point planner.
- Parameters
setup (
SBLSetup
) – [in] Setup for the planner.
-
static
makeQToQSamplerPlanner
(setup)¶ An SBL based sampled region planner.
- Parameters
setup (
SBLSetup
) – [in] Setup for the planner.
-
static
makeQToTPlanner
(setup, ikSampler)¶ An SBL based point-to-tool-position planner.
- Parameters
setup (
SBLSetup
) – [in] Setup for the planner.ikSampler (rw::core::Ptr< QIKSampler >) – [in] Sampler of IK solutions for the target transform.
-
property
thisown
¶ The membership flag
-
static
-
class
sdurw_pathplanners.
SBLPlannerConstraint
(qconstraint, edgeconstraint)¶ Bases:
object
A SBL planner constraint.
-
getEdgeConstraint
()¶ Get the part that checks edges in-between valid configurations.
- Return type
- Returns
a reference to the edge constraint.
-
getQConstraint
()¶ Get the part that checks for valid configurations.
- Return type
- Returns
a reference to the constraint.
-
property
thisown
¶ The membership flag
-
-
class
sdurw_pathplanners.
SBLPlannerPtr
(*args)¶ Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
-
deref
()¶ The pointer stored in the object.
-
getDeref
()¶ Member access operator.
-
isNull
()¶ checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null
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.
-
makeQToQPlanner
(setup)¶ An SBL based point-to-point planner.
- Parameters
setup (
SBLSetup
) – [in] Setup for the planner.
-
makeQToQSamplerPlanner
(setup)¶ An SBL based sampled region planner.
- Parameters
setup (
SBLSetup
) – [in] Setup for the planner.
-
makeQToTPlanner
(setup, ikSampler)¶ An SBL based point-to-tool-position planner.
- Parameters
setup (
SBLSetup
) – [in] Setup for the planner.ikSampler (rw::core::Ptr< QIKSampler >) – [in] Sampler of IK solutions for the target transform.
-
property
thisown
¶ The membership flag
-
-
sdurw_pathplanners.
SBLPlanner_makeQToQPlanner
(setup)¶ An SBL based point-to-point planner.
- Parameters
setup (
SBLSetup
) – [in] Setup for the planner.
-
sdurw_pathplanners.
SBLPlanner_makeQToQSamplerPlanner
(setup)¶ An SBL based sampled region planner.
- Parameters
setup (
SBLSetup
) – [in] Setup for the planner.
-
sdurw_pathplanners.
SBLPlanner_makeQToTPlanner
(setup, ikSampler)¶ An SBL based point-to-tool-position planner.
- Parameters
setup (
SBLSetup
) – [in] Setup for the planner.ikSampler (rw::core::Ptr< QIKSampler >) – [in] Sampler of IK solutions for the target transform.
-
class
sdurw_pathplanners.
SBLSetup
(*args, **kwargs)¶ Bases:
object
Common parameters for SBL based planners.
All versions of the SBL planner base verify configurations and paths in the configuration space using a PlannerConstraint object.
In addition, parameters can given to define how expansion around a node of the tree should be done and under what circumstances the two trees should be connected.
A SBLSetup object stores pointers to the shared objects, but can be copied and assigned freely.
-
static
make
(*args)¶ Overload 1:
Constructor
The SBL planner for this setup performs brute force search for the nearest neighbor of the other tree, and attempts to connect the trees if the distance to the neighbor is below a given threshold.
- Parameters
constraint (rw::core::Ptr< QConstraint >) – [in] Planning constraint.
edgeConstraint (rw::core::Ptr< QEdgeConstraintIncremental >) – [in] Planning constraint for edges.
expansion (rw::core::Ptr< SBLExpand >) – [in] Expansion strategy for insertion of new nodes. The nodes returned by the expansion strategy must be collision free or empty. If an empty configuration is returned, the planner tries to expand somewhere else.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Distance metric for nearest neighbor searching.
connectRadius (float) – [in] Attempt connection of the trees if the distance to the nearest neighbor is below this threshold.
Overload 2:
Constructor
Simple default expansion and tree connection strategies are chosed based on the device for which the planning is done.
The planner expands uniformly at random with a maximum stepsize of expandRadius relative to the diameter of the configuration space. The step size and the diameter is measured by the infinity metric.
The planner connect a newly created node to the nearest node of the other tree if the distance to the other node (measured by the infinity metric and relative to the diameter of the configuration space) is less than connectRadius.
If expandRadius or connectRadius is negative, a default value is chosen.
- Parameters
constraint (rw::core::Ptr< QConstraint >) – [in] Planning constraint.
edgeConstraint (rw::core::Ptr< QEdgeConstraintIncremental >) – [in] Planning constraint for edges.
device (rw::core::Ptr< Device >) – [in] Device for which planning is done.
expandRadius (float) – [in] Node expansion radius.
connectRadius (float) – [in] Neighbor connection radius.
Overload 3:
Constructor
Simple default expansion and tree connection strategies are chosed based on the device for which the planning is done.
The planner expands uniformly at random with a maximum stepsize of expandRadius relative to the diameter of the configuration space. The step size and the diameter is measured by the infinity metric.
The planner connect a newly created node to the nearest node of the other tree if the distance to the other node (measured by the infinity metric and relative to the diameter of the configuration space) is less than connectRadius.
If expandRadius or connectRadius is negative, a default value is chosen.
- Parameters
constraint (rw::core::Ptr< QConstraint >) – [in] Planning constraint.
edgeConstraint (rw::core::Ptr< QEdgeConstraintIncremental >) – [in] Planning constraint for edges.
device (rw::core::Ptr< Device >) – [in] Device for which planning is done.
expandRadius (float) – [in] Node expansion radius.
connectRadius – [in] Neighbor connection radius.
Overload 4:
Constructor
Simple default expansion and tree connection strategies are chosed based on the device for which the planning is done.
The planner expands uniformly at random with a maximum stepsize of expandRadius relative to the diameter of the configuration space. The step size and the diameter is measured by the infinity metric.
The planner connect a newly created node to the nearest node of the other tree if the distance to the other node (measured by the infinity metric and relative to the diameter of the configuration space) is less than connectRadius.
If expandRadius or connectRadius is negative, a default value is chosen.
- Parameters
constraint (rw::core::Ptr< QConstraint >) – [in] Planning constraint.
edgeConstraint (rw::core::Ptr< QEdgeConstraintIncremental >) – [in] Planning constraint for edges.
device (rw::core::Ptr< Device >) – [in] Device for which planning is done.
expandRadius – [in] Node expansion radius.
connectRadius – [in] Neighbor connection radius.
-
property
options
¶ Internal options to use.
-
property
thisown
¶ The membership flag
-
static
-
sdurw_pathplanners.
SBLSetup_make
(*args)¶ Overload 1:
Constructor
The SBL planner for this setup performs brute force search for the nearest neighbor of the other tree, and attempts to connect the trees if the distance to the neighbor is below a given threshold.
- Parameters
constraint (rw::core::Ptr< QConstraint >) – [in] Planning constraint.
edgeConstraint (rw::core::Ptr< QEdgeConstraintIncremental >) – [in] Planning constraint for edges.
expansion (rw::core::Ptr< SBLExpand >) – [in] Expansion strategy for insertion of new nodes. The nodes returned by the expansion strategy must be collision free or empty. If an empty configuration is returned, the planner tries to expand somewhere else.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Distance metric for nearest neighbor searching.
connectRadius (float) – [in] Attempt connection of the trees if the distance to the nearest neighbor is below this threshold.
Overload 2:
Constructor
Simple default expansion and tree connection strategies are chosed based on the device for which the planning is done.
The planner expands uniformly at random with a maximum stepsize of expandRadius relative to the diameter of the configuration space. The step size and the diameter is measured by the infinity metric.
The planner connect a newly created node to the nearest node of the other tree if the distance to the other node (measured by the infinity metric and relative to the diameter of the configuration space) is less than connectRadius.
If expandRadius or connectRadius is negative, a default value is chosen.
- Parameters
constraint (rw::core::Ptr< QConstraint >) – [in] Planning constraint.
edgeConstraint (rw::core::Ptr< QEdgeConstraintIncremental >) – [in] Planning constraint for edges.
device (rw::core::Ptr< Device >) – [in] Device for which planning is done.
expandRadius (float) – [in] Node expansion radius.
connectRadius (float) – [in] Neighbor connection radius.
Overload 3:
Constructor
Simple default expansion and tree connection strategies are chosed based on the device for which the planning is done.
The planner expands uniformly at random with a maximum stepsize of expandRadius relative to the diameter of the configuration space. The step size and the diameter is measured by the infinity metric.
The planner connect a newly created node to the nearest node of the other tree if the distance to the other node (measured by the infinity metric and relative to the diameter of the configuration space) is less than connectRadius.
If expandRadius or connectRadius is negative, a default value is chosen.
- Parameters
constraint (rw::core::Ptr< QConstraint >) – [in] Planning constraint.
edgeConstraint (rw::core::Ptr< QEdgeConstraintIncremental >) – [in] Planning constraint for edges.
device (rw::core::Ptr< Device >) – [in] Device for which planning is done.
expandRadius (float) – [in] Node expansion radius.
connectRadius – [in] Neighbor connection radius.
Overload 4:
Constructor
Simple default expansion and tree connection strategies are chosed based on the device for which the planning is done.
The planner expands uniformly at random with a maximum stepsize of expandRadius relative to the diameter of the configuration space. The step size and the diameter is measured by the infinity metric.
The planner connect a newly created node to the nearest node of the other tree if the distance to the other node (measured by the infinity metric and relative to the diameter of the configuration space) is less than connectRadius.
If expandRadius or connectRadius is negative, a default value is chosen.
- Parameters
constraint (rw::core::Ptr< QConstraint >) – [in] Planning constraint.
edgeConstraint (rw::core::Ptr< QEdgeConstraintIncremental >) – [in] Planning constraint for edges.
device (rw::core::Ptr< Device >) – [in] Device for which planning is done.
expandRadius – [in] Node expansion radius.
connectRadius – [in] Neighbor connection radius.
-
class
sdurw_pathplanners.
Z3Planner
(*args, **kwargs)¶ Bases:
object
Z3 based planners
See “The Z3-Method for Fast Path Planning in Dynamic Environments”, Boris Baginski, 1996.
-
static
makeQToQPlanner
(*args)¶ Overload 1:
Z3 based point-to-point planner.
- Parameters
sampler (rw::core::Ptr< QSampler >) – [in] Sampler of the configuration space.
localPlanner (rw::core::Ptr< QToQPlanner >) – [in] Local planner for connecting the configurations.
nodeCnt (int) – [in] Number of supporting configurations to insert. If nodeCnt is negative, a default value is chosen.
repeatCnt (int) – [in] Number of times to repeat the attempt. If repeatCnt is negative (the default), the attempts are repeated until the stop criteria returns true.
Overload 2:
Z3 based point-to-point planner.
A default configuration space sampler (rw::pathplanning::QSampler) and local planning is chosen for device using constraint for collision checking.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
-
static
makeSlidingQToQPlanner
(*args)¶ Overload 1:
Sliding local planner.
This is a variation of the sliding local planner described in the Z3 paper.
This is the default local planner used for instantiation of the Z3 based planners.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
directionSampler (rw::core::Ptr< QSampler >) – [in] Sampler of direction vectors in the configuration space.
boundsConstraint (rw::core::Ptr< QConstraint >) – [in] Constraint checking for the bounds of the configuration space.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure.
extend (float) – [in] The length of each sliding step as measured by metric.
slideImprovement (float) – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 2:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend (float) – [in] The length of each sliding step as measured by metric.
slideImprovement (float) – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 3:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend (float) – [in] The length of each sliding step as measured by metric.
slideImprovement – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 4:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend – [in] The length of each sliding step as measured by metric.
slideImprovement – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 5:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend – [in] The length of each sliding step as measured by metric.
slideImprovement – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
-
property
thisown
¶ The membership flag
-
static
-
class
sdurw_pathplanners.
Z3PlannerPtr
(*args)¶ Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
-
deref
()¶ The pointer stored in the object.
-
getDeref
()¶ Member access operator.
-
isNull
()¶ checks if the pointer is null :rtype: boolean :return: Returns true if the pointer is null
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.
-
makeQToQPlanner
(*args)¶ Overload 1:
Z3 based point-to-point planner.
- Parameters
sampler (rw::core::Ptr< QSampler >) – [in] Sampler of the configuration space.
localPlanner (rw::core::Ptr< QToQPlanner >) – [in] Local planner for connecting the configurations.
nodeCnt (int) – [in] Number of supporting configurations to insert. If nodeCnt is negative, a default value is chosen.
repeatCnt (int) – [in] Number of times to repeat the attempt. If repeatCnt is negative (the default), the attempts are repeated until the stop criteria returns true.
Overload 2:
Z3 based point-to-point planner.
A default configuration space sampler (rw::pathplanning::QSampler) and local planning is chosen for device using constraint for collision checking.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
-
makeSlidingQToQPlanner
(*args)¶ Overload 1:
Sliding local planner.
This is a variation of the sliding local planner described in the Z3 paper.
This is the default local planner used for instantiation of the Z3 based planners.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
directionSampler (rw::core::Ptr< QSampler >) – [in] Sampler of direction vectors in the configuration space.
boundsConstraint (rw::core::Ptr< QConstraint >) – [in] Constraint checking for the bounds of the configuration space.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure.
extend (float) – [in] The length of each sliding step as measured by metric.
slideImprovement (float) – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 2:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend (float) – [in] The length of each sliding step as measured by metric.
slideImprovement (float) – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 3:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend (float) – [in] The length of each sliding step as measured by metric.
slideImprovement – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 4:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend – [in] The length of each sliding step as measured by metric.
slideImprovement – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 5:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend – [in] The length of each sliding step as measured by metric.
slideImprovement – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
-
property
thisown
¶ The membership flag
-
-
sdurw_pathplanners.
Z3Planner_makeQToQPlanner
(*args)¶ Overload 1:
Z3 based point-to-point planner.
- Parameters
sampler (rw::core::Ptr< QSampler >) – [in] Sampler of the configuration space.
localPlanner (rw::core::Ptr< QToQPlanner >) – [in] Local planner for connecting the configurations.
nodeCnt (int) – [in] Number of supporting configurations to insert. If nodeCnt is negative, a default value is chosen.
repeatCnt (int) – [in] Number of times to repeat the attempt. If repeatCnt is negative (the default), the attempts are repeated until the stop criteria returns true.
Overload 2:
Z3 based point-to-point planner.
A default configuration space sampler (rw::pathplanning::QSampler) and local planning is chosen for device using constraint for collision checking.
- Parameters
constraint (PlannerConstraint) – [in] Constraint for configurations and edges.
device (rw::core::Ptr< Device >) – [in] Device for which the path is planned.
-
sdurw_pathplanners.
Z3Planner_makeSlidingQToQPlanner
(*args)¶ Overload 1:
Sliding local planner.
This is a variation of the sliding local planner described in the Z3 paper.
This is the default local planner used for instantiation of the Z3 based planners.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
directionSampler (rw::core::Ptr< QSampler >) – [in] Sampler of direction vectors in the configuration space.
boundsConstraint (rw::core::Ptr< QConstraint >) – [in] Constraint checking for the bounds of the configuration space.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure.
extend (float) – [in] The length of each sliding step as measured by metric.
slideImprovement (float) – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 2:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend (float) – [in] The length of each sliding step as measured by metric.
slideImprovement (float) – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 3:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend (float) – [in] The length of each sliding step as measured by metric.
slideImprovement – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 4:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric (rw::core::Ptr< rw::math::Metric< Q > >) – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend – [in] The length of each sliding step as measured by metric.
slideImprovement – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
Overload 5:
Sliding local planner.
A default direction sampler and bounds checker is chosen for device.
- Parameters
constraint (PlannerConstraint) – [in] Path planning constraint.
device (rw::core::Ptr< Device >) – [in] Device for which the planning is done.
metric – [in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend – [in] The length of each sliding step as measured by metric.
slideImprovement – [in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.
-
sdurw_pathplanners.
makeToNearestRRT
(cdect, dev)¶
-
sdurw_pathplanners.
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.