# Frequently Asked Questions {#FAQ} - 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](installation.html) and [Updating Python Bindings](python.html#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](buildSystem.html). 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](stateValidation.html). - 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](http://graphml.graphdrawing.org) which can be read by a number of external programs such a [graph-tool](https://graph-tool.skewed.de) and [Gephi](https://gephi.github.io). - 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: ~~~{.cpp} #include "ompl/base/samplers/ObstacleBasedValidStateSampler.h" ... ompl::base::ValidStateSamplerPtr allocValidStateSampler(const ompl::base::SpaceInformation *si) { return ompl::base::ValidStateSamplerPtr(new ompl::base::ObstacleBasedValidStateSampler(si)); } ... ompl::base::StateSpacePtr space(...); ompl::base::SpaceInformationPtr si(new ompl::base::SpaceInformation(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](http://sourceforge.net/mailarchive/forum.php?forum_name=ompl-users).