Package org.robwork.sdurw_pathplanners
Class PRMPlannerPtr
- java.lang.Object
-
- org.robwork.sdurw_pathplanners.PRMPlannerPtr
-
public class PRMPlannerPtr extends java.lang.Object
Ptr stores a pointer and optionally takes ownership of the value.
-
-
Constructor Summary
Constructors Constructor Description PRMPlannerPtr()
Default constructor yielding a NULL-pointer.PRMPlannerPtr(long cPtr, boolean cMemoryOwn)
PRMPlannerPtr(PRMPlanner ptr)
Do not take ownership of ptr.
ptr can be null.
The constructor is implicit on purpose.
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description PRMPlanner
__ref__()
Dereferencing operator.void
buildRoadmap(long nodecount)
Build the roadmap with the setup specified
void
delete()
PRMPlanner
deref()
The pointer stored in the object.boolean
equals(PRMPlanner p)
static long
getCPtr(PRMPlannerPtr obj)
PRMPlanner
getDeref()
Member access operator.PropertyMap
getProperties()
Property map for the planner.boolean
isNull()
checks if the pointer is nullboolean
isShared()
check if this Ptr has shared ownership or none
ownershipQToQPlannerPtr
make(PlannerConstraint constraint)
Construct a path planner from an edge constraint.
The path planners calls the edge constraint to verify if the path
going directly from the start to goal configuration can be traversed.
The configuration constraint is called to verify that neither the
start nor end configuration is in collision.
QToQPlannerPtr
make(QToQSamplerPlannerPtr planner)
Construct a path planner from a region planner.
The region planner is given as goal region the single to
configuration passed to the query() method.
void
printTimeStats()
print timing stats from previous run.boolean
query(Q from, Q to, SWIGTYPE_p_rw__trajectory__PathT_rw__math__Q_t path)
Plan a path from the configuration from to the destination
to.
The planner runs until it gives up (which may be never).
boolean
query(Q from, Q to, SWIGTYPE_p_rw__trajectory__PathT_rw__math__Q_t path, double time)
Plan a path from the configuration from to the destination
to.
boolean
query(Q from, Q to, SWIGTYPE_p_rw__trajectory__PathT_rw__math__Q_t path, StopCriteria stop)
Plan a path from the configuration from to the destination
to.
void
setAStarTimeOutTime(double 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.void
setCollisionCheckingStrategy(PRMPlanner.CollisionCheckingStrategy collisionCheckingStrategy)
Sets up the collision checking strategy
Note: Do not call this after the buildRoadmap as it may result in paths with collisions
void
setNeighborCount(long n)
Sets the desired average number of neighbors.void
setNeighSearchStrategy(PRMPlanner.NeighborSearchStrategy neighborSearchStrategy)
Sets up the nearest neighbor search strategy
void
setPartialIndexTableDimensions(long 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()].void
setShortestPathSearchStrategy(PRMPlanner.ShortestPathSearchStrategy shortestPathSearchStrategy)
Sets up the shortest path search strategy
Generally A* is the fastest algorithm, but given a small roadmap Dijkstra may
perform better.
-
-
-
Constructor Detail
-
PRMPlannerPtr
public PRMPlannerPtr(long cPtr, boolean cMemoryOwn)
-
PRMPlannerPtr
public PRMPlannerPtr()
Default constructor yielding a NULL-pointer.
-
PRMPlannerPtr
public PRMPlannerPtr(PRMPlanner ptr)
Do not take ownership of ptr.
ptr can be null.
The constructor is implicit on purpose.
-
-
Method Detail
-
getCPtr
public static long getCPtr(PRMPlannerPtr obj)
-
delete
public void delete()
-
deref
public PRMPlanner deref()
The pointer stored in the object.
-
__ref__
public PRMPlanner __ref__()
Dereferencing operator.
-
getDeref
public PRMPlanner getDeref()
Member access operator.
-
equals
public boolean equals(PRMPlanner p)
-
isShared
public boolean isShared()
check if this Ptr has shared ownership or none
ownership- Returns:
- true if Ptr has shared ownership, false if it has no ownership.
-
isNull
public boolean isNull()
checks if the pointer is null- Returns:
- Returns true if the pointer is null
-
buildRoadmap
public void buildRoadmap(long nodecount)
Build the roadmap with the setup specified
- Parameters:
nodecount
- [in] Number of nodes to insert
-
setNeighborCount
public void setNeighborCount(long n)
Sets the desired average number of neighbors. Default value is 20.
- Parameters:
n
- [in] Desired average number of neighbors
-
setNeighSearchStrategy
public void setNeighSearchStrategy(PRMPlanner.NeighborSearchStrategy neighborSearchStrategy)
Sets up the nearest neighbor search strategy
- Parameters:
neighborSearchStrategy
- [in] The nearest neighbor search strategy
-
setPartialIndexTableDimensions
public void setPartialIndexTableDimensions(long 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
- [in] Number of dimensions, which should be
-
setCollisionCheckingStrategy
public void setCollisionCheckingStrategy(PRMPlanner.CollisionCheckingStrategy 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
- [in] The collision checking strategy
-
setShortestPathSearchStrategy
public void setShortestPathSearchStrategy(PRMPlanner.ShortestPathSearchStrategy 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
- [in] shortestPathSearchStrategy
-
setAStarTimeOutTime
public void setAStarTimeOutTime(double 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
- [in] Timeout time.
-
printTimeStats
public void printTimeStats()
print timing stats from previous run.
-
make
public QToQPlannerPtr make(QToQSamplerPlannerPtr planner)
Construct a path planner from a region planner.
The region planner is given as goal region the single to
configuration passed to the query() method.
- Parameters:
planner
- [in] A planner for a region given by a QSampler.
-
make
public QToQPlannerPtr make(PlannerConstraint constraint)
Construct a path planner from an edge constraint.
The path planners calls the edge constraint to verify if the path
going directly from the start to goal configuration can be traversed.
The configuration constraint is called to verify that neither the
start nor end configuration is in collision.
- Parameters:
constraint
- [in] Planner constraint.- Returns:
- A planner that attempts the directly connecting edge only.
-
query
public boolean query(Q from, Q to, SWIGTYPE_p_rw__trajectory__PathT_rw__math__Q_t path, StopCriteria stop)
Plan a path from the configuration from to the destination
to.
- Parameters:
from
- [in] start configuration for path.
to
- [in] end destination of path.
path
- [out] a collision free path connecting from to to.
stop
- [in] Abort the planning when stop returns true.
- Returns:
- true if a path between from from to to was found and
false otherwise.
-
query
public boolean query(Q from, Q to, SWIGTYPE_p_rw__trajectory__PathT_rw__math__Q_t path, double time)
Plan a path from the configuration from to the destination
to.
- Parameters:
from
- [in] start configuration for path.
to
- [in] end destination of path.
path
- [out] a collision free path connecting from to to.
time
- [in] Abort the planning after time seconds.
- Returns:
- true if a path between from from to to was found and
false otherwise.
-
query
public boolean query(Q from, Q to, SWIGTYPE_p_rw__trajectory__PathT_rw__math__Q_t path)
Plan a path from the configuration from to the destination
to.
The planner runs until it gives up (which may be never).
- Parameters:
from
- [in] start configuration for path.
to
- [in] end destination of path.
path
- [out] a collision free path connecting from to to.
- Returns:
- true if a path between from from to to was found and
false otherwise.
-
getProperties
public PropertyMap getProperties()
Property map for the planner.
-
-