Robowflex
v0.1
Making MoveIt Easy
|
#include <moveit/planning_pipeline/planning_pipeline.h>
#include <robowflex_library/class_forward.h>
#include <robowflex_library/constants.h>
#include <robowflex_library/pool.h>
#include <robowflex_library/io/handler.h>
#include <robowflex_library/robot.h>
#include <robowflex_library/scene.h>
Go to the source code of this file.
Classes | |
class | robowflex::Planner |
An abstract interface to a motion planning algorithm. More... | |
class | robowflex::PoolPlanner |
A thread pool of planners P to service requests in a multi-threaded environment simultaneously. More... | |
class | robowflex::SimpleCartesianPlanner |
A simple motion planner that uses interpolation of the end-effector in Cartesian space to find a path. Valid configurations are found using IK. This planner is not complete and typically only works for small movements of the end-effector. More... | |
class | robowflex::PipelinePlanner |
A motion planner that uses the MoveIt! planning pipeline to load a planner plugin. More... | |
class | robowflex::OMPL::Settings |
Settings descriptor for settings provided by the default MoveIt! OMPL planning pipeline. More... | |
class | robowflex::OMPL::OMPLPipelinePlanner |
A robowflex::PipelinePlanner that uses the MoveIt! default OMPL planning pipeline. More... | |
class | robowflex::opt::CHOMPSettings |
Settings descriptor for settings provided by the default MoveIt! CHOMP planning pipeline. More... | |
class | robowflex::opt::CHOMPPipelinePlanner |
A robowflex::PipelinePlanner that uses the MoveIt! CHOMP planning pipeline. More... | |
class | robowflex::opt::TrajOptPipelinePlanner |
A robowflex::PipelinePlanner that uses the MoveIt! TrajOpt planning pipeline. More... | |
Namespaces | |
robowflex | |
Main namespace. Contains all library classes and functions. | |
robowflex::OMPL | |
OMPL specific planners and features. | |
robowflex::opt | |
Functions | |
bool | robowflex::OMPL::loadOMPLConfig (IO::Handler &handler, const std::string &config_file, std::vector< std::string > &configs) |
Loads an OMPL configuration YAML file onto the parameter server. More... | |
bool | robowflex::opt::loadConfig (IO::Handler &handler, const std::string &config_file) |
Loads configuration YAML file onto the parameter server. More... | |