sdurw_pathoptimization module
- class sdurw_pathoptimization.sdurw_pathoptimization.ClearanceCalculator(*args, **kwargs)
Bases:
object
Interface for ClearanceCalculator
A ClearanceCalculator provides a mean for calculating the clearance of for a state. While the concept of clearance usually refers to the distance between a device and obstacle, not such assumption should be made based on the interface, as other fitness criteria may be implemented.
Only convention is that a high clearance value is better than a low.
- clearance(state)
Calculates Clearance for the state
- Parameters
state (
State
) – [in] State for which to calculate the clearance- Return type
float
- Returns
The clearance.
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.ClearanceCalculatorCPtr(*args)
Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
- clearance(state)
Calculates Clearance for the state
- Parameters
state (
State
) – [in] State for which to calculate the clearance- Return type
float
- Returns
The clearance.
- 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.
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.ClearanceCalculatorPtr(*args)
Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
- clearance(state)
Calculates Clearance for the state
- Parameters
state (
State
) – [in] State for which to calculate the clearance- Return type
float
- Returns
The clearance.
- cptr()
- 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.
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.ClearanceOptimizer(device, state, metric, clearanceCalculator)
Bases:
object
The ClearanceOptimizer implements the C-Retraction algorithms from [1]
[1]: R. Geraerts and M.H. Overmars, Creating High-Quality Paths for Motion Planning, The International Journal of Robotics Research, Vol. 26, No. 8, 845-863 (2007)
The algorithms work by first subdividing the path, to give a dense and even distribution of nodes along the path. Nodes are then tried moved in a random direction to improve the clearance. After having iterated through the entire path some nodes will be moved, thus a validation step is used to insert extra nodes where the density is not high enough. This is then followed by a method for removing undesired branches.
- PROP_LOOPCOUNT = 'LoopCount'
- PROP_MAXTIME = 'MaxTime'
- PROP_STEPSIZE = 'StepSize'
- getClearanceCalculator()
Returns the ClearanceCalculator associated with the optimizer.
- Return type
rw::core::Ptr< rwlibs::pathoptimization::ClearanceCalculator const >
- Returns
Const reference to the ClearanceCalculator.
- getMinimumClearance()
Returns the minimum clearance optimized for. :rtype: float :return: The minimum clearance.
- getPropertyMap()
Returns the PropertyMap associated with the optimizer.
The PropertyMap defines the following parameters used by the optimizer:
Property Name | Type | Default value ———————————- | —— | ————- ClearanceOptimizer::PROP_LOOPCOUNT | int | 20 ClearanceOptimizer::PROP_MAXTIME | double | 200 ClearanceOptimizer::PROP_STEPSIZE | double | 0.1
- Return type
PropertyMap
- Returns
The PropertyMap
- optimize(*args)
Overload 1:
Runs optimization algorithm
Calling this method runs the path optimization algorithm. This call blocks until the optimized path is ready. This may take quite a while, depending on the maxcount specified and the amount of geometry in the scene.
- Parameters
path (rw::trajectory::QPath) – [in] Path to optimize
stepsize (float) – [in] Maximum size between configurations in the dense path
maxcount (int) – [in] Number of time to attempt optimizing the path using the random direction. If maxcount=0 only the maxtime will be used.
maxtime (float) – [in] The maximal time allowed to optimize. If maxtime**<=0 only the **maxcount will be used
- Return type
rw::trajectory::QPath
- Returns
The optimized path with node no further than stepsize apart
Overload 2:
Runs optimization algorithm
Runs the optimization algorithm using the parameters specified in the property map
- Parameters
path (rw::trajectory::QPath) – [in] Path to optimize
- Return type
rw::trajectory::QPath
- Returns
The optimized path
- setMinimumClearance(dist)
Sets the minimum clearance optimized for. Points on the path with clearance greater than _minClearance are not optimized further. Class default value is 0.1 meters. Value must be equal to or greater than zero.
- Parameters
dist (float) – [in] Minimum clearance.
- setQConstraint(qConstraint)
Set a configuration constraint in the clearance optimizer.
The optimizer will not generate a path with configurations that is in collision according to the constraint.
- Parameters
qConstraint (rw::core::Ptr< rw::pathplanning::QConstraint const >) – [in] the constraint.
- setStateConstraint(stateConstraint)
Set a state constraint in the clearance optimizer.
The optimizer will not generate a path with configurations that is in collision according to the state constraint.
- Parameters
stateConstraint (rw::core::Ptr< rw::pathplanning::StateConstraint const >) – [in] the constraint.
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.ClearanceOptimizerCPtr(*args)
Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
- property PROP_LOOPCOUNT
Property key for the maximal number of loops. Set LOOPCOUNT=0 to deactivate it
- property PROP_MAXTIME
Property key for max time. Set MAXTIME=0 to deactivate it
- property PROP_STEPSIZE
Property key for step size
- deref()
The pointer stored in the object.
- getClearanceCalculator()
Returns the ClearanceCalculator associated with the optimizer.
- Return type
rw::core::Ptr< rwlibs::pathoptimization::ClearanceCalculator const >
- Returns
Const reference to the ClearanceCalculator.
- getDeref()
Member access operator.
- getMinimumClearance()
Returns the minimum clearance optimized for. :rtype: float :return: The minimum clearance.
- 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.
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.ClearanceOptimizerPtr(*args)
Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
- property PROP_LOOPCOUNT
Property key for the maximal number of loops. Set LOOPCOUNT=0 to deactivate it
- property PROP_MAXTIME
Property key for max time. Set MAXTIME=0 to deactivate it
- property PROP_STEPSIZE
Property key for step size
- cptr()
- deref()
The pointer stored in the object.
- getClearanceCalculator()
Returns the ClearanceCalculator associated with the optimizer.
- Return type
rw::core::Ptr< rwlibs::pathoptimization::ClearanceCalculator const >
- Returns
Const reference to the ClearanceCalculator.
- getDeref()
Member access operator.
- getMinimumClearance()
Returns the minimum clearance optimized for. :rtype: float :return: The minimum clearance.
- getPropertyMap()
Returns the PropertyMap associated with the optimizer.
The PropertyMap defines the following parameters used by the optimizer:
Property Name | Type | Default value ———————————- | —— | ————- ClearanceOptimizer::PROP_LOOPCOUNT | int | 20 ClearanceOptimizer::PROP_MAXTIME | double | 200 ClearanceOptimizer::PROP_STEPSIZE | double | 0.1
- Return type
PropertyMap
- Returns
The PropertyMap
- 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.
- optimize(*args)
Overload 1:
Runs optimization algorithm
Calling this method runs the path optimization algorithm. This call blocks until the optimized path is ready. This may take quite a while, depending on the maxcount specified and the amount of geometry in the scene.
- Parameters
path (rw::trajectory::QPath) – [in] Path to optimize
stepsize (float) – [in] Maximum size between configurations in the dense path
maxcount (int) – [in] Number of time to attempt optimizing the path using the random direction. If maxcount=0 only the maxtime will be used.
maxtime (float) – [in] The maximal time allowed to optimize. If maxtime**<=0 only the **maxcount will be used
- Return type
rw::trajectory::QPath
- Returns
The optimized path with node no further than stepsize apart
Overload 2:
Runs optimization algorithm
Runs the optimization algorithm using the parameters specified in the property map
- Parameters
path (rw::trajectory::QPath) – [in] Path to optimize
- Return type
rw::trajectory::QPath
- Returns
The optimized path
- setMinimumClearance(dist)
Sets the minimum clearance optimized for. Points on the path with clearance greater than _minClearance are not optimized further. Class default value is 0.1 meters. Value must be equal to or greater than zero.
- Parameters
dist (float) – [in] Minimum clearance.
- setQConstraint(qConstraint)
Set a configuration constraint in the clearance optimizer.
The optimizer will not generate a path with configurations that is in collision according to the constraint.
- Parameters
qConstraint (rw::core::Ptr< rw::pathplanning::QConstraint const >) – [in] the constraint.
- setStateConstraint(stateConstraint)
Set a state constraint in the clearance optimizer.
The optimizer will not generate a path with configurations that is in collision according to the state constraint.
- Parameters
stateConstraint (rw::core::Ptr< rw::pathplanning::StateConstraint const >) – [in] the constraint.
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.MinimumClearanceCalculator(*args)
Bases:
ClearanceCalculator
Implements a MinimumClearanceCalculator
The minimum clearance is defined as the minimal distance between any two geometries, which are not excluded by the collision setup.
- clearance(state)
Calculates Clearance for the state
- Parameters
state (
State
) – [in] State for which to calculate the clearance- Return type
float
- Returns
The clearance.
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.MinimumClearanceCalculatorCPtr(*args)
Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
- clearance(state)
- 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.
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.MinimumClearanceCalculatorPtr(*args)
Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
- clearance(state)
- cptr()
- 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.
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.PathLengthOptimizer(constraint, metric)
Bases:
object
The PathLengthOptimizer implements the 3 different path length optimizers presented in [1].
[1]: R. Geraerts and M.H. Overmars, Creating High-Quality Paths for Motion Planning, The International Journal of Robotics Research, Vol. 26, No. 8, 845-863 (2007)
The simplest algorithm pathPruning runs through the path an tests if nodes with index i and i+2 can be directly connected. If so it removed node i+1.
The shortCut algorithm works similary except that it takes two random indices i and j and tries to connect those. This algorithm is non-deterministic but more powerful than pathPruning.
The partialShortCut algorithm select two random node indices i and j and a random position in the configuration vector. A shortcut is then only tried between the values corresponding to the random position. This algorithm is generally more powerful than shortCut but may in some cases be more computational expensive.
- PROP_LOOPCOUNT = 'LoopCount'
- PROP_MAXTIME = 'MaxTime'
- PROP_SUBDIVLENGTH = 'SubDivideLength'
- getPropertyMap()
Returns the propertymap :rtype:
PropertyMap
:return: Reference to the property map
- partialShortCut(*args)
Overload 1:
Optimizes using the partial shortcut technique
The partialShortCut algorithm select two random node indices i and j and a random position in the configuration vector. A shortcut is then only tried between the values corresponding to the random position.
The algorithm will loop until either the specified cnt is of met or the specified time is reached.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
cnt (int) – [in] Max count to use. If cnt=0, only the time limit will be used
time (float) – [in] Max time to use (in seconds). If time=0, only the cnt limit will be used
subDivideLength (float) – [in] The length into which the path is subdivided
Overload 2:
Optimizes using the partial shortcut technique
Works similar to partialShortCut(const rw::pathplanning::Path&, size_t, double, double) except that parameters are read from the propertymap.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
- Return type
rw::trajectory::QPath
- Returns
The optimized path
- pathPruning(path)
Optimizes using path pruning.
pathPruning runs through the path an tests if nodes with index i and i+2 can be directly connected. If so it removes node i+1.
- Parameters
path (rw::trajectory::QPath) – [in] Path to optimize
- shortCut(*args)
Overload 1:
Optimizes using the shortcut technique
The shortCut algorithm works by selecting two random indices i and j and try to connect those.
The algorithm will loop until either the specified cnt is of met or the specified time is reached.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
cnt (int) – [in] Max count to use. If cnt=0, only the time limit will be used
time (float) – [in] Max time to use (in seconds). If time=0, only the cnt limit will be used
subDivideLength (float) – [in] The length into which the path is subdivided
Overload 2:
Optimizes using the shortcut technique
Works similar to shortCut(const rw::pathplanning::Path&, size_t, double, double) except that parameters are read from the propertymap.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.PathLengthOptimizerCPtr(*args)
Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
- property PROP_LOOPCOUNT
Property key for the maximal number of loops
- property PROP_MAXTIME
Property key for max time
- property PROP_SUBDIVLENGTH
Property key for length of segment in when subdividing
- 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.
- partialShortCut(*args)
Overload 1:
Optimizes using the partial shortcut technique
The partialShortCut algorithm select two random node indices i and j and a random position in the configuration vector. A shortcut is then only tried between the values corresponding to the random position.
The algorithm will loop until either the specified cnt is of met or the specified time is reached.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
cnt (int) – [in] Max count to use. If cnt=0, only the time limit will be used
time (float) – [in] Max time to use (in seconds). If time=0, only the cnt limit will be used
subDivideLength (float) – [in] The length into which the path is subdivided
Overload 2:
Optimizes using the partial shortcut technique
Works similar to partialShortCut(const rw::pathplanning::Path&, size_t, double, double) except that parameters are read from the propertymap.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
- Return type
rw::trajectory::QPath
- Returns
The optimized path
- pathPruning(path)
Optimizes using path pruning.
pathPruning runs through the path an tests if nodes with index i and i+2 can be directly connected. If so it removes node i+1.
- Parameters
path (rw::trajectory::QPath) – [in] Path to optimize
- shortCut(*args)
Overload 1:
Optimizes using the shortcut technique
The shortCut algorithm works by selecting two random indices i and j and try to connect those.
The algorithm will loop until either the specified cnt is of met or the specified time is reached.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
cnt (int) – [in] Max count to use. If cnt=0, only the time limit will be used
time (float) – [in] Max time to use (in seconds). If time=0, only the cnt limit will be used
subDivideLength (float) – [in] The length into which the path is subdivided
Overload 2:
Optimizes using the shortcut technique
Works similar to shortCut(const rw::pathplanning::Path&, size_t, double, double) except that parameters are read from the propertymap.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
- property thisown
The membership flag
- class sdurw_pathoptimization.sdurw_pathoptimization.PathLengthOptimizerPtr(*args)
Bases:
object
Ptr stores a pointer and optionally takes ownership of the value.
- property PROP_LOOPCOUNT
Property key for the maximal number of loops
- property PROP_MAXTIME
Property key for max time
- property PROP_SUBDIVLENGTH
Property key for length of segment in when subdividing
- cptr()
- deref()
The pointer stored in the object.
- getDeref()
Member access operator.
- getPropertyMap()
Returns the propertymap :rtype:
PropertyMap
:return: Reference to the property map
- 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.
- partialShortCut(*args)
Overload 1:
Optimizes using the partial shortcut technique
The partialShortCut algorithm select two random node indices i and j and a random position in the configuration vector. A shortcut is then only tried between the values corresponding to the random position.
The algorithm will loop until either the specified cnt is of met or the specified time is reached.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
cnt (int) – [in] Max count to use. If cnt=0, only the time limit will be used
time (float) – [in] Max time to use (in seconds). If time=0, only the cnt limit will be used
subDivideLength (float) – [in] The length into which the path is subdivided
Overload 2:
Optimizes using the partial shortcut technique
Works similar to partialShortCut(const rw::pathplanning::Path&, size_t, double, double) except that parameters are read from the propertymap.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
- Return type
rw::trajectory::QPath
- Returns
The optimized path
- pathPruning(path)
Optimizes using path pruning.
pathPruning runs through the path an tests if nodes with index i and i+2 can be directly connected. If so it removes node i+1.
- Parameters
path (rw::trajectory::QPath) – [in] Path to optimize
- shortCut(*args)
Overload 1:
Optimizes using the shortcut technique
The shortCut algorithm works by selecting two random indices i and j and try to connect those.
The algorithm will loop until either the specified cnt is of met or the specified time is reached.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
cnt (int) – [in] Max count to use. If cnt=0, only the time limit will be used
time (float) – [in] Max time to use (in seconds). If time=0, only the cnt limit will be used
subDivideLength (float) – [in] The length into which the path is subdivided
Overload 2:
Optimizes using the shortcut technique
Works similar to shortCut(const rw::pathplanning::Path&, size_t, double, double) except that parameters are read from the propertymap.
- Parameters
path (rw::trajectory::QPath) – [inout] Path to optimize
- property thisown
The membership flag
- sdurw_pathoptimization.sdurw_pathoptimization.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.
Overload 323:
A Ptr that takes ownership over a raw pointer ptr.
Overload 324:
A Ptr that takes ownership over a raw pointer ptr.
Overload 325:
A Ptr that takes ownership over a raw pointer ptr.