RobWorkProject
23.9.11-
|
Implements a probabilistic roadmap (PRM) planner. More...
#include <PRMPlanner.hpp>
Inherits QToQPlanner.
Public Types | |
enum | NeighborSearchStrategy { BRUTE_FORCE = 0 , PARTIAL_INDEX_TABLE , KDTREE } |
Enumeration for selecting the node neighbor search strategy. More... | |
enum | CollisionCheckingStrategy { LAZY = 0 , NODECHECK , FULL } |
Enumeration for selecting the collision checking strategy. More... | |
enum | ShortestPathSearchStrategy { A_STAR = 0 , DIJKSTRA } |
Enumeration for selecing the shortest path search strategy. More... | |
typedef rw::core::Ptr< PRMPlanner > | Ptr |
smart pointer type to this class | |
Public Types inherited from QToQPlanner | |
typedef rw::core::Ptr< QToQPlanner > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< const QToQPlanner > | CPtr |
smart pointer type to this const class | |
Public Types inherited from PathPlanner< rw::math::Q, const rw::math::Q > | |
typedef rw::core::Ptr< PathPlanner > | Ptr |
smart pointer type to this class | |
Public Member Functions | |
PRMPlanner (rw::models::Device *device, const rw::kinematics::State &state, rw::proximity::CollisionDetector *collisionDetector, double resolution) | |
Constructs PRMPlanner. More... | |
PRMPlanner (rw::core::Ptr< rw::pathplanning::QConstraint > constraint, rw::core::Ptr< rw::pathplanning::QSampler > sampler, double resolution, const rw::models::Device &device, const rw::kinematics::State &state) | |
Constructs PRMPlanner. More... | |
virtual | ~PRMPlanner () |
Destructor. | |
void | buildRoadmap (size_t nodecount) |
Build the roadmap with the setup specified. More... | |
void | setNeighborCount (size_t n) |
Sets the desired average number of neighbors. Default value is 20. More... | |
void | setNeighSearchStrategy (NeighborSearchStrategy neighborSearchStrategy) |
Sets up the nearest neighbor search strategy. More... | |
void | setPartialIndexTableDimensions (size_t dimensions) |
Sets up the number of dimensions for the partial index table. More... | |
void | setCollisionCheckingStrategy (CollisionCheckingStrategy collisionCheckingStrategy) |
Sets up the collision checking strategy. More... | |
void | setShortestPathSearchStrategy (ShortestPathSearchStrategy shortestPathSearchStrategy) |
Sets up the shortest path search strategy. More... | |
void | setAStarTimeOutTime (double timeout) |
Sets the max time of A* before terminating and calling dijkstra. More... | |
void | printTimeStats () |
print timing stats from previous run. | |
Public Member Functions inherited from PathPlanner< rw::math::Q, const rw::math::Q > | |
virtual | ~PathPlanner () |
Destructor. | |
bool | query (const rw::math::Q &from, const rw::math::Q &to, rw::trajectory::Path< rw::math::Q > &path, const StopCriteria &stop) |
Plan a path from the configuration from to the destination to. More... | |
bool | query (const rw::math::Q &from, const rw::math::Q &to, rw::trajectory::Path< rw::math::Q > &path, double time) |
Plan a path from the configuration from to the destination to. More... | |
bool | query (const rw::math::Q &from, const rw::math::Q &to, rw::trajectory::Path< rw::math::Q > &path) |
Plan a path from the configuration from to the destination to. More... | |
core::PropertyMap & | getProperties () |
Property map for the planner. | |
const core::PropertyMap & | getProperties () const |
Property map for the planner. | |
Additional Inherited Members | |
Static Public Member Functions inherited from QToQPlanner | |
static QToQPlanner::Ptr | make (rw::core::Ptr< QToQSamplerPlanner > planner) |
Construct a path planner from a region planner. More... | |
static QToQPlanner::Ptr | make (const PlannerConstraint &constraint) |
Construct a path planner from an edge constraint. More... | |
Protected Member Functions inherited from PathPlanner< rw::math::Q, const rw::math::Q > | |
PathPlanner () | |
Default constructor provided for subclasses. | |
Implements a probabilistic roadmap (PRM) planner.
The PRMPlanner is implemented freely after [1], and has a number of options:
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
[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
PRMPlanner | ( | rw::models::Device * | device, |
const rw::kinematics::State & | state, | ||
rw::proximity::CollisionDetector * | collisionDetector, | ||
double | resolution | ||
) |
Constructs PRMPlanner.
Constructs a PRMPlanner with a given setup. This method does NOT build the roadmap. The method estimates the movements of the robot to construct a weighted metric as explained in the general introduction.
device | [in] Device to plan for |
state | [in] State giving the setup of the workcell |
collisionDetector | [in] CollisionDetector to use |
resolution | [in] Cartesian distance the robot is allowed to move between collision checks. |
PRMPlanner | ( | rw::core::Ptr< rw::pathplanning::QConstraint > | constraint, |
rw::core::Ptr< rw::pathplanning::QSampler > | sampler, | ||
double | resolution, | ||
const rw::models::Device & | device, | ||
const rw::kinematics::State & | state | ||
) |
Constructs PRMPlanner.
constraint | [in] Collision constraint |
sampler | [in] Configuration space sampler |
resolution | [in] Collision checking resolution |
device | [in] Device characteristics |
state | [in] State of rest of the workcell |
void buildRoadmap | ( | size_t | nodecount | ) |
Build the roadmap with the setup specified.
nodecount | [in] Number of nodes to insert |
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.
timeout | [in] Timeout time. |
void setCollisionCheckingStrategy | ( | CollisionCheckingStrategy | collisionCheckingStrategy | ) |
Sets up the collision checking strategy.
Note: Do not call this after the buildRoadmap as it may result in paths with collisions
collisionCheckingStrategy | [in] The collision checking strategy |
void setNeighborCount | ( | size_t | n | ) |
Sets the desired average number of neighbors. Default value is 20.
n | [in] Desired average number of neighbors |
void setNeighSearchStrategy | ( | NeighborSearchStrategy | neighborSearchStrategy | ) |
Sets up the nearest neighbor search strategy.
neighborSearchStrategy | [in] The nearest neighbor search strategy |
void setPartialIndexTableDimensions | ( | size_t | 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.
dimensions | [in] Number of dimensions, which should be |
void setShortestPathSearchStrategy | ( | ShortestPathSearchStrategy | shortestPathSearchStrategy | ) |
Sets up the shortest path search strategy.
Generally A* is the fastest algorithm, but given a small roadmap Dijkstra may perform better.
shortestPathSearchStrategy | [in] shortestPathSearchStrategy |