INTRODUCTION
Overview
Download and Install
Quick Start
Documentation
Publications

NONFRAMEWORK CODE
Driver Interfaces
Drivers
Libraries
Utilities

FRAMEWORK CODE
Interfaces
Components
Libraries
Utilities

Full Software Listings

DEVELOPER
Tutorials
Examples
Dev Guide
Dashboard

PEOPLE
Contributors
Users

SourceForge.net Logo
Project
Download
Mailing lists

 

         

PathPlanner
[ComponentsStand-Alone ComponentsIceBox ServicesC++LinuxQNX]

Computes a path in a 2D occupancy grid map. More...

Computes a path in a 2D occupancy grid map.

The pathplanner acts like a service receiving tasks from third parties and returning a computed path in a 2D world represented by an occupancy grid map. An example for a third party is the orca_component_pathplantester.

Provides
  • orca_interface_home
  • orca_interface_qgraphics2d [PathPlanner.Provides.Graphics] (Skeleton navigation and Sparse Skeleton navigation algorithms only)
  • orca_interface_pathplanner2d [PathPlanner.Provides.PathPlanner2d]
  • orca_interface_status
Requires
  • orca_interface_ogmap [PathPlanner.Requires.OgMap]
pathplanner.png
Algorithms
Configuration
  • PathPlanner.Config.Algorithm (string)
    • Type of algorithm
    • Valid values: { 'simplenav', 'skeletonnav', 'sparseskeletonnav', 'astar' }
    • Default: 'sparseskeletonnav'
  • PathPlanner.Config.TraversabilityThreshhold (double)
    • Everything below this threshhold is considered traversable, everything above is an obstacle
    • Valid values: [0.0;1.0]
    • Default: 0.6
  • PathPlanner.Config.RobotDiameterMetres (double) [m]
    • The robot's diameter including some safety distance
    • Default: 0.8
  • PathPlanner.Config.DoPathOptimization (bool)
  • PathPlanner.Config.JiggleWaypointsOntoClearCells (bool)
    • Currently only works for sparse skeleton!!!
    • If true, incoming paths will be fixed up by moving waypoints off of obstacles.
    • Valid values: 0 or 1
    • Default: 1
  • PathPlanner.Config.Skeleton.Cost.DistanceThreshold (double)
    • (For skeleton-based path-planning only):
      • If a path causes the robot to clear an obstacle by less than DistanceThreshold, the cost of that portion of the path is multiplied by CostMultiplier.
      • Default: 0.3
  • PathPlanner.Config.Skeleton.Cost.CostMultiplier (double)
    • (For skeleton-based path-planning only):
      • If a path causes the robot to clear an obstacle by less than DistanceThreshold, the cost of that portion of the path is multiplied by CostMultiplier.
      • Default: 10
  • PathPlanner.Config.Skeleton.SparseSkelAddExtraNodes (bool)
    • (For sparse-skeleton-based path-planning only):
      • Add extra nodes every to avoid weird things happening in sparse areas.
      • Default: 1
  • PathPlanner.Config.Skeleton.SparseSkelExtraNodeResolution (double)
    • (For sparse-skeleton-based path-planning only):
      • Add extra nodes every this-many metres if SparseSkelAddExtraNodes is set.
      • Default: 5.0
  • PathPlanner.Config.Skeleton.ProvideGraphics (bool)
    • (For skeleton-based path-planning only):
      • If true, provide a QGraphics2d interface showing the skeleton.
      • Default: 1

An example configuration file is installed into [ORCA-INSTALL-DIR]/share/orca/cfg/ directory.

Algorithms

Algorithms are listed below. The quoted (approximate) speed of each algorithm is for a Release build, for a single path segment on a 500x500-cell world.

Simple navigation

This algorithm is described in Latombe, "Robot Motion Planning", sec. 4.2.1. It is a simple grid-potential based method using wavefront propagation. We added the consideration of the robot platform's size.

  • Speed:
    • No pre-computation required.
    • ~0.5sec to plan a path.

Skeleton navigation

This algorithm is described in Latombe, "Robot Motion Planning", sec. 4.2.2. It computes an improved numverical navigation function by first extracting a skeleton.

  • Speed: the current implementation is fairly slow.
    • ~0.3sec to pre-compute the skeleton.
    • ~0.2sec to plan a path.

Sparse Skeleton navigation

This algorithm uses the Skeleton navigation algorithm. After generating a dense skeleton, it extracts a sparse set of nodes and arcs between those nodes. This is much faster to plan on.

  • Speed:
    • ~1sec to pre-compute the skeleton.
    • <1ms to plan a path.
Note on diplaying skeletons

Both skeleton navigation algorithms can display the computed skeleton in OrcaView2d using the orca_interface_qgraphics2d interface. This is useful for debugging purposes. The skeleton is not part of the orca_interface_pathplanner2d interface data.

Path optimization algorithm

This algorithm takes a fine-grained path and tries to find shortcuts by raytracing between waypoints. If no obstacle is in the way it will discard all the waypoints in between. The path it computes contains much fewer waypoints than the original path. A negative side-effect is that the path gets close to the walls but the local navigation should take care of this.

A* search

This algorithm uses the famous A* search algorithm to guarantee the shortest path from start to goal. The heuristic takes diagonal traversing into account. Original implementation was done by Pham Ngoc Hai (h dot pham at acfr.usyd.edu.au).

  • Speed:
    • No pre-computation required
    • To plan path: depends heavily on the particular path
      • A* has known problems if it needs to 'fill up' a potential bowl.
      • Rough guide: ~10ms to ~10sec.
Notes

Bibtex reference to the LaTombe book which contains the gridpotential-based algorithms (Simple navigation and Skeleton navigation):

@Book{latombe91robot,
  author    =    {Jean-Claude Latombe},
  title =        {Robot Motion Planning},
  publisher =    {Kluwer Academic Publishers},
  year =         {1991}
}
Authors
  • Tobias Kaupp
  • Sparse Skeleton Stuff: Alex Brooks
 

Webmaster: Tobias Kaupp (tobasco at users.sourceforge.net)


Generated for Orca Robotics by  doxygen 1.4.5