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

Classes

class  CHOMPSettings
 Settings descriptor for settings provided by the default MoveIt! CHOMP planning pipeline. More...
 
class  CHOMPPipelinePlanner
 A robowflex::PipelinePlanner that uses the MoveIt! CHOMP planning pipeline. More...
 
class  TrajOptPipelinePlanner
 A robowflex::PipelinePlanner that uses the MoveIt! TrajOpt planning pipeline. More...
 

Functions

bool loadConfig (IO::Handler &handler, const std::string &config_file)
 Loads configuration YAML file onto the parameter server. More...
 

Function Documentation

◆ loadConfig()

bool robowflex::opt::loadConfig ( IO::Handler handler,
const std::string config_file 
)

Loads configuration YAML file onto the parameter server.

Opt

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

387 {
388  if (config_file.empty())
389  return false;
390 
391  const auto &config = IO::loadFileToYAML(config_file);
392  if (!config.first)
393  {
394  RBX_ERROR("Failed to load planner configs.");
395  return false;
396  }
397 
398  handler.loadYAMLtoROS(config.second);
399 
400  return true;
401 }
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.