Almost all of the functionality of the C++ OMPL library is accessible through Python using more or less the same API. Some important differences will be described below. The Python bindings are generated with Py++, which relies on Boost.Python. The bindings are packaged in the ompl module. The main namespaces (ompl::base, ompl::control, ompl::geometric) are available as sub-modules. To quickly get an idea of what classes, functions, etc., are available within each submodule, type something like this at the Python prompt:
>>> from ompl import base, control, geometric, util
>>> dir(base), dir(control), dir(geometric), dir(util)
function_call(Constructor_call())
), so it's advisable to create variables with the appropriate scope.spc = SE3StateSpace() # create an SE(3) state space s = State(spc) # allocate a state corresponding to a C++ ScopedState<SE3StateSpace> sref = s() # sref corresponds to a C++ State*. In this case sref is # a reference SE3StateSpace::StateType sref.setX(1.0) # set the X coordinate s().setX(1.0) # this also works
foo.print(std::cout)
becomes print foo
in python. Similarly, a C++ call like foo.printSettings(std::cout)
becomes print foo.settings()
in python.def isStateValid(spaceInformation, state): return spaceInformation.satiesfiesBounds(state)
Many of the python demo and test programs are direct ports of the corresponding C++ programs. If you compare these programs, the sometimes subtle differences will become more obvious. In the python programs you will notice that we can create python classes that derive from C++ classes and pass instances of such classes to C++ functions. Similarly, we can create python functions (such as state validity checkers or propagate functions) that can be called by C++ code.
Below is a simple annotated example. It is available in ompl/py-bindings/demos/RigidBodyPlanning.py.
from ompl import base as ob from ompl import geometric as og def isStateValid(spaceInformation, state): # "state" is of type SE2StateInternal, so we don't need to use the "()" # operator. # # Some arbitrary condition on the state (note that thanks to # dynamic type checking we can just call getX() and do not need # to convert state to an SE2State.) return state.getX() < .6 def plan(): # create an SE2 state space space = ob.SE2StateSpace() # set lower and upper bounds bounds = ob.RealVectorBounds(2) bounds.setLow(-1) bounds.setHigh(1) space.setBounds(bounds) # create a simple setup object ss = og.SimpleSetup(space) ss.setStateValidityChecker(isStateValid) start = ob.State(space) # we can pick a random start state... start.random() # ... or set specific values start().setX(.5) goal = ob.State(space) # we can pick a random goal state... goal.random() # ... or set specific values goal().setY(-.5) ss.setStartAndGoalStates(start, goal) # this will automatically choose a default planner with # default parameters solved = ss.solve(1.0) if solved: # try to shorten the path ss.simplifySolution() # print the simplified path print ss.getSolutionPath() if __name__ == "__main__": plan()
The Python bindings are subdivided into modules, to reflect the main namespaces: ompl::base, ompl::control, and ompl::geometric. The code in the ompl/src/ompl/util directory is available in a submodule as well. Whenever you change the API to OMPL, you will need to update the Python bindings. Updating the bindings is a two-step process. First, the code for the modules needs to be generated. Second, the code needs to be compiled into binary Python modules.
The code for the Python bindings can be generated by typing “make update_bindings
.” This creates one header file per module, formed by concatenating all relevant header files for that module. This header file is then parsed by Py++ and the appropriate C++ code is generated. This code uses Boost.Python. Py++ is smart enough to create wrapper classes when necessary, register Python <-> C++ type conversions, and so on. If you only need to update the bindings for one module (say base
), you can type “make update_base_bindings
.” Any diagnostic information from Py++ is stored in a log file in the build directory for each module (pyplusplus_base.log
for the module base
and likewise for other modules).
For each module the relevant header files are listed in ompl/py-bindings/headers_<modulename>.txt.
The order in which the header files are listed is important. A header file should not be included by another header file listed above it.
To compile the Python modules type “make py_ompl
.” If you only want to compile one python module (say base
), type “make py_ompl_base
.” The modules will appear as libraries in the lib subdirectory in the build directory, but they are also copied to ompl/py-bindings/ompl/<modulename>/_<modulename>.so
.
Every attempt has been to have CMake correctly identify dependencies and only compile code when necessary. If you want force CMake to regenerate the bindings from scratch, you can remove the directory ompl/py-bindings/bindings
and type “make update_bindings
” again. If, on the other hand, you want to (temporarily) disable the compilation of Python bindings, type:
cmake -D OMPL_BUILD_PYBINDINGS:BOOL=OFF .
in your build directory. You can re-enable them, by running this command again, but with OFF changed to ON. Changing these settings can also be done through the CMake GUI.