Q: Why are the Python bindings not built?
Short answer (most likely case): after running
cmake
, type “make update_bindings
”.Long answer: the bindings are automatically generated by a script. You may not have all dependencies correctly installed (or detected by cmake). Check the pages Installation and Updating Python Bindings for details on installing dependencies and the individual steps involved in creating Python bindings, respectively.
Q: Why is the code I added to the OMPL source not being compiled?
See the OMPL Build System. Essentially, just run
cmake
again after adding new files.Q: How do I specify collision checking for a planner?
A: See page on state validation.
Q: Can I visualize the exploration data structure used by a planner?
A: Yes. You need to call ompl::base::Planner::getPlannerData(). This will give you an instance of ompl::base::PlannerData which contains all the states and the edges between them. The PlannerData can be exported in GraphML format which can be read by a number of external programs such a graph-tool and Gephi.
Q: Can I change the state space during planning?
A: No. Such changes will make the code crash.
Q: Can I set the sampler to use for a planner?
A: Yes. The sampler instances used by planners are allocated by either ompl::base::SpaceInformation::allocStateSampler() (which calls ompl::base::StateSpace::allocStateSampler() under the hood) or by ompl::base::SpaceInformation::allocValidStateSampler(). By default, ompl::base::SpaceInformation::allocValidStateSampler() produces an instance of ompl::base::UniformValidStateSampler, unless a sampler allocator was specified. The simplest way to change which sampler is allocated is to specify a sampler allocator. Calling ompl::base::SpaceInformation::setValidStateSamplerAllocator() allows the user to do just that:
#include "ompl/base/samplers/ObstacleBasedValidStateSampler.h"...ompl::base::ValidStateSamplerPtr allocValidStateSampler(const ompl::base::SpaceInformation *si){}...ompl::base::StateSpacePtr space(...);si->setValidStateSamplerAllocator(std::bind(&allocValidStateSampler, std::placeholders::_1));// for simplified calls, you can also use:// si->setValidStateSamplerAllocator(&allocValidStateSampler);The example above is similarly applicable for ompl::base::StateSamplerAllocator ompl::control::ControlSamplerAllocator, ompl::control::DirectedControlSamplerAllocator and ompl::base::PlannerAllocator.
If your question is still not answered, another good place to check is the mailing list archive.