Implementing a New Motion Planner {#newPlanner}

Strict Requirements

Implementing a new motion planner is very simple using OMPL. There are just two strict requirements:

  • Publicly derive the new class from ompl::base::Planner

  • Provide an implementation of the method solve() from ompl::base::Planner.

By satisfying these requirements, the planner can be fully integrated within the existing OMPL framework.

Optional Features

Aside from the strict requirements, there are other methods which can be implemented and practices which should be followed for ease of integration. These are not required, but are strongly recommended for simplicity and consistency:

  • Update the values of the ompl::base::PlannerSpecs member of ompl::base::Planner in the constructor of your planner to indicate its capabilities to the user.

  • Overload ompl::base::Planner::setup (if needed) to execute any one-time setup methods. Note that setup() is only guaranteed to be called once, and is not likely to be invoked before each call to solve().

  • When a solution path is found in the solve() method, save it to the instance of ompl::base::ProblemDefinition using its addSolutionPath member. ompl::base::ProblemDefinition is a member of ompl::base::Planner.

  • Return an informative value from ompl::base::PlannerStatus in the implementation of solve().

  • solve() should respect the ompl::base::PlannerTerminationCondition argument passed to it. When the given condition evaluates true, solve() should return as quickly as possible.

  • Repeated calls to solve() should not restart the planning process from scratch, but rather pick up the search where it left off previously.

  • Provide an implementation of ompl::base::Planner::clear(). This method should free any memory allocated by the planner and restore the planner to a state where ompl::base::Planner::solve() can be called again (without passing on information from previous calls to solve() ). If necessary, clear() can set ompl::base::Planner::setup_ to false, to communicate to solve() that setup() needs to be called again.

  • Provide an implementation of ompl::bas::Planner::getPlannerData() which translates the internal planner data structure to the ompl::base::PlannerData graph implementation. This method is particularly useful for debugging purposes since it allows the user to inspect the data structure.

New Planner Template

The following is a template which can be used to craft a new ompl::base::Planner object: