Robowflex  v0.1
Making MoveIt Easy
robowflex::OMPL Namespace Reference

OMPL specific planners and features. More...

Classes

class  Cob4OMPLPipelinePlanner
 Convenience class for the default motion planning pipeline for Cob4. More...
 
class  FetchOMPLPipelinePlanner
 Convenience class for the default motion planning pipeline for Fetch. More...
 
class  R2OMPLPipelinePlanner
 Convenience class for the default motion planning pipeline for R2 (R2C6 full). More...
 
class  UR5OMPLPipelinePlanner
 Convenience class for the default motion planning pipeline for UR5. More...
 
class  Settings
 Settings descriptor for settings provided by the default MoveIt! OMPL planning pipeline. More...
 
class  OMPLPipelinePlanner
 A robowflex::PipelinePlanner that uses the MoveIt! default OMPL planning pipeline. More...
 
class  OMPLInterfacePlanner
 A planner that directly uses MoveIt!'s OMPL planning interface. More...
 
class  OMPLTrajectory
 OMPLTrajectory provides OMPL path utilities to the Trajectory class. More...
 

Functions

bool 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...
 

Detailed Description

OMPL specific planners and features.

Function Documentation

◆ loadOMPLConfig()

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.

OMPL

Definition at line 271 of file robowflex_library/src/planning.cpp.

273 {
274  if (config_file.empty())
275  return false;
276 
277  const auto &config = IO::loadFileToYAML(config_file);
278  if (!config.first)
279  {
280  RBX_ERROR("Failed to load planner configs.");
281  return false;
282  }
283 
284  handler.loadYAMLtoROS(config.second);
285 
286  const auto &planner_configs = config.second["planner_configs"];
287  if (planner_configs)
288  {
289  for (YAML::const_iterator it = planner_configs.begin(); it != planner_configs.end(); ++it)
290  configs.push_back(it->first.as<std::string>());
291  }
292 
293  return true;
294 }
void loadYAMLtoROS(const YAML::Node &node, const std::string &prefix="")
Loads the contents of a YAML node to the parameter server under a prefix.
T empty(T... args)
#define RBX_ERROR(fmt,...)
Output a error logging message.
Definition: log.h:102
std::pair< bool, YAML::Node > loadFileToYAML(const std::string &path)
Loads a file to a YAML node.
T push_back(T... args)