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

File and ROS Input / Output operations. More...

Classes

class  Bag
 rosbag management class to ease message saving and loading. More...
 
class  RobotBroadcaster
 Helper class to broadcast transform information on TF and joint states. More...
 
class  GNUPlotHelper
 Helper class to open a pipe to a GNUPlot instance for live visualization of data. More...
 
class  GNUPlotPlanDataSetOutputter
 Helper class to plot a real metric as a box plot using GNUPlot from benchmarking data. More...
 
class  Handler
 ROS parameter server handler to handle namespacing and automatic parameter deletion. More...
 
class  HDF5Data
 A container class for HDF5 DataSets loaded by an HDF5File. More...
 
class  HDF5File
 An HDF5 File loaded into memory. More...
 
class  PluginManager
 A singleton class for dynamic loading classes through pluginlib. More...
 
class  RVIZHelper
 RVIZ visualization helper. See Live Visualization with RViz for more information. More...
 

Functions

bool isNode (const YAML::Node &node)
 Checks if a key exists within a YAML node. More...
 
moveit_msgs::RobotState robotStateFromNode (const YAML::Node &node)
 Converts a robot state YAML to a robot_state message. More...
 
YAML::Node toNode (const geometry_msgs::Pose &msg)
 Converts a pose message to YAML. More...
 
geometry_msgs::Pose poseFromNode (const YAML::Node &node)
 Converts a pose YAML to a goemetry message. More...
 
YAML::Node toNode (const moveit_msgs::PlanningScene &msg)
 Converts a planning scene message to YAML. More...
 
YAML::Node toNode (const moveit_msgs::MotionPlanRequest &msg)
 Converts a motion plan request to YAML. More...
 
YAML::Node toNode (const moveit_msgs::RobotTrajectory &msg)
 Converts a motion plan to YAML. More...
 
YAML::Node toNode (const moveit_msgs::RobotState &msg)
 Converts a robot state to YAML. More...
 
bool fromYAMLFile (moveit_msgs::PlanningScene &msg, const std::string &file)
 Loads a planning scene from a YAML file. More...
 
bool fromYAMLFile (moveit_msgs::MotionPlanRequest &msg, const std::string &file)
 Loads a motion planning request from a YAML file. More...
 
bool fromYAMLFile (moveit_msgs::RobotState &msg, const std::string &file)
 Loads a robot state from a YAML file. More...
 
std::string generateUUID ()
 Generates a UUID. More...
 
std::string resolvePackage (const std::string &path)
 Resolves package:// URLs to their canonical form. The path does not need to exist, but the package does. Can be used to write new files in packages. More...
 
std::set< std::stringfindPackageURIs (const std::string &string)
 Finds all package URIs within a string. More...
 
std::string resolvePath (const std::string &path)
 Resolves package:// URLs and relative file paths to their canonical form. More...
 
std::string resolveParent (const std::string &path)
 Resolves package:// URLs to get the directory this path is in. More...
 
std::string makeFilepath (const std::string &directory, const std::string &filename)
 Concatenates two elements of a path, a directory and a filename. More...
 
std::string loadXMLToString (const std::string &path)
 Loads an XML or .xacro file to a string. More...
 
std::string loadXacroToString (const std::string &path)
 Loads a .xacro file to a string. More...
 
std::string loadFileToString (const std::string &path)
 Loads a file to a string. More...
 
std::string runCommand (const std::string &cmd)
 Runs a command cmd and returns stdout as a string. More...
 
std::pair< bool, YAML::Node > loadFileToYAML (const std::string &path)
 Loads a file to a YAML node. More...
 
std::pair< bool, std::vector< YAML::Node > > loadAllFromFileToYAML (const std::string &path)
 Loads a file with multiple documents to a vector of YAML nodes. More...
 
void createFile (std::ofstream &out, const std::string &file)
 Creates a file and opens an output stream. Creates directories if they do not exist. More...
 
std::string createTempFile (std::ofstream &out)
 Creates a temporary file and opens an output stream. More...
 
void deleteFile (const std::string &file)
 Deletes a file. More...
 
std::pair< bool, std::vector< std::string > > listDirectory (const std::string &directory)
 Lists of the contents of a directory. More...
 
std::string getHostname ()
 Get the hostname of the system. More...
 
std::size_t getProcessID ()
 Get the process ID of this process. More...
 
std::size_t getThreadID ()
 Get the thread ID of the current thread. More...
 
boost::posix_time::ptime getDate ()
 Get the current time (up to milliseconds) More...
 
double getSeconds (boost::posix_time::ptime start, boost::posix_time::ptime finish)
 Get a duration in seconds from two times. More...
 
void threadSleep (double seconds)
 Put the current thread to sleep for a desired amount of seconds. More...
 
template<typename T >
std::vector< T > tokenize (const std::string &string, const std::string &separators=" ")
 Separates a string into casted tokens, based upon separators. More...
 
bool YAMLToFile (const YAML::Node &node, const std::string &file)
 Write the contents of a YAML node out to a potentially new file. More...
 
template<typename T >
bool messageToYAMLFile (T &msg, const std::string &file)
 Dump a message (or YAML convertable object) to a file. More...
 
template<typename T >
bool YAMLFileToMessage (T &msg, const std::string &file)
 Load a message (or YAML convertable object) from a file. More...
 
template<typename T >
std::string getMessageMD5 (T &msg)
 Compute MD5 hash of message. More...
 

Detailed Description

File and ROS Input / Output operations.

Function Documentation

◆ createFile()

void robowflex::IO::createFile ( std::ofstream out,
const std::string file 
)

Creates a file and opens an output stream. Creates directories if they do not exist.

Parameters
[out]outOutput stream to initialize.
[in]fileFile to create and open.

Definition at line 296 of file robowflex_library/src/io.cpp.

297 {
298  boost::filesystem::path path(file);
299  path = expandHome(path);
300  path = expandSymlinks(path);
301 
302  const auto parent = path.parent_path().string();
303 
304  if (!parent.empty())
305  boost::filesystem::create_directories(parent);
306 
307  out.open(path.string(), std::ofstream::out | std::ofstream::trunc);
308 }
T open(T... args)

◆ createTempFile()

std::string robowflex::IO::createTempFile ( std::ofstream out)

Creates a temporary file and opens an output stream.

Parameters
[out]outOutput stream to initialize.
Returns
Filename of temporary file.

Definition at line 310 of file robowflex_library/src/io.cpp.

311 {
312  auto temp = boost::filesystem::unique_path();
313  auto filename = "/tmp/" + temp.string();
314  createFile(out, filename);
315 
316  return filename;
317 }
void createFile(std::ofstream &out, const std::string &file)
Creates a file and opens an output stream. Creates directories if they do not exist.

◆ deleteFile()

void robowflex::IO::deleteFile ( const std::string file)

Deletes a file.

Parameters
[in]fileFile to delete.

Definition at line 319 of file robowflex_library/src/io.cpp.

320 {
321  boost::filesystem::path path(file);
322  path = expandHome(path);
323  path = expandSymlinks(path);
324 
325  boost::filesystem::remove(path);
326 }

◆ findPackageURIs()

std::set< std::string > robowflex::IO::findPackageURIs ( const std::string string)

Finds all package URIs within a string.

Parameters
[in]stringString to search.
Returns
List of package URIs.

Definition at line 118 of file robowflex_library/src/io.cpp.

119 {
120  const std::regex re(R"(((package):?\/)\/?([^:\/\s]+)((\/\w+)*\/)([\w\-\.]+[^#?\s]+)?)");
121 
122  std::set<std::string> packages;
123 
124  auto begin = std::sregex_iterator(string.begin(), string.end(), re);
125  auto end = std::sregex_iterator();
126 
127  for (auto it = begin; it != end; ++it)
128  {
129  std::smatch sm = *it;
130  std::string smstr = sm.str(3);
131  packages.emplace(smstr);
132  }
133 
134  return packages;
135 }
T begin(T... args)
T emplace(T... args)
T end(T... args)
T str(T... args)

◆ fromYAMLFile() [1/3]

bool robowflex::IO::fromYAMLFile ( moveit_msgs::MotionPlanRequest msg,
const std::string file 
)

Loads a motion planning request from a YAML file.

Parameters
[out]msgMessage to load into.
[in]fileFile to load.
Returns
True on success, false on failure.

Definition at line 1919 of file yaml.cpp.

1920  {
1921  return IO::YAMLFileToMessage(msg, file);
1922  }
bool YAMLFileToMessage(T &msg, const std::string &file)
Load a message (or YAML convertable object) from a file.

◆ fromYAMLFile() [2/3]

bool robowflex::IO::fromYAMLFile ( moveit_msgs::PlanningScene &  msg,
const std::string file 
)

Loads a planning scene from a YAML file.

Parameters
[out]msgMessage to load into.
[in]fileFile to load.
Returns
True on success, false on failure.

Definition at line 1914 of file yaml.cpp.

1915  {
1916  return IO::YAMLFileToMessage(msg, file);
1917  }

◆ fromYAMLFile() [3/3]

bool robowflex::IO::fromYAMLFile ( moveit_msgs::RobotState &  msg,
const std::string file 
)

Loads a robot state from a YAML file.

Parameters
[out]msgMessage to load into.
[in]fileFile to load.
Returns
True on success, false on failure.

Definition at line 1924 of file yaml.cpp.

1925  {
1926  return IO::YAMLFileToMessage(msg, file);
1927  }

◆ generateUUID()

std::string robowflex::IO::generateUUID ( )

Generates a UUID.

Returns
String of UUID.

Definition at line 284 of file robowflex_library/src/io.cpp.

285 {
286  boost::uuids::random_generator gen;
287  boost::uuids::uuid u = gen();
288 
289  std::string s = boost::lexical_cast<std::string>(u);
290 
291  std::replace(s.begin(), s.end(), '-', '_');
292 
293  return s;
294 }
T replace(T... args)

◆ getDate()

boost::posix_time::ptime robowflex::IO::getDate ( )

Get the current time (up to milliseconds)

Returns
The time.

Definition at line 362 of file robowflex_library/src/io.cpp.

363 {
364  return boost::posix_time::microsec_clock::local_time();
365 }

◆ getHostname()

std::string robowflex::IO::getHostname ( )

Get the hostname of the system.

Returns
String of the hostname.

Definition at line 347 of file robowflex_library/src/io.cpp.

348 {
349  return boost::asio::ip::host_name();
350 }

◆ getMessageMD5()

template<typename T >
std::string robowflex::IO::getMessageMD5 ( T &  msg)

Compute MD5 hash of message.

Parameters
[in]msgMessage to hash.
Template Parameters
TType of the message.
Returns
The hash of the message.

Definition at line 206 of file robowflex_library/include/robowflex_library/io.h.

207  {
208  return ros::message_traits::md5sum<T>(msg);
209  }

◆ getProcessID()

std::size_t robowflex::IO::getProcessID ( )

Get the process ID of this process.

Returns
The process ID.

Definition at line 352 of file robowflex_library/src/io.cpp.

353 {
354  return boost::interprocess::ipcdetail::get_current_process_id();
355 }

◆ getSeconds()

double robowflex::IO::getSeconds ( boost::posix_time::ptime  start,
boost::posix_time::ptime  finish 
)

Get a duration in seconds from two times.

Parameters
[in]startThe start time.
[in]finishThe finish time.
Returns
The time in seconds.

Definition at line 367 of file robowflex_library/src/io.cpp.

368 {
369  auto duration = finish - start;
370  return duration.total_microseconds() / 1000000.;
371 }

◆ getThreadID()

std::size_t robowflex::IO::getThreadID ( )

Get the thread ID of the current thread.

Returns
The thread ID.

Definition at line 357 of file robowflex_library/src/io.cpp.

358 {
359  return boost::interprocess::ipcdetail::get_current_thread_id();
360 }

◆ isNode()

bool robowflex::IO::isNode ( const YAML::Node &  node)

Checks if a key exists within a YAML node.

Parameters
[in]nodeNode to check.
Returns
True if the node exists and is not null.

Definition at line 1847 of file yaml.cpp.

1848  {
1849  try
1850  {
1851  bool r = node.IsDefined() and not node.IsNull();
1852  if (r)
1853  try
1854  {
1855  r = node.as<std::string>() != "~";
1856  }
1857  catch (std::exception &e)
1858  {
1859  }
1860 
1861  return r;
1862  }
1863  catch (YAML::InvalidNode &e)
1864  {
1865  return false;
1866  }
1867  }

◆ listDirectory()

std::pair< bool, std::vector< std::string > > robowflex::IO::listDirectory ( const std::string directory)

Lists of the contents of a directory.

Parameters
[in]directoryDirectory to list.
Returns
A pair of a bool and a vector of strings of filenames of the directories contents. The first element will be true on success, false on failure. These filenames are absolute paths.

Definition at line 328 of file robowflex_library/src/io.cpp.

329 {
330  std::vector<std::string> contents;
331 
332  const std::string full_path = resolvePath(directory);
333  if (full_path.empty())
334  return std::make_pair(false, contents);
335 
336  boost::filesystem::path path(full_path);
337  if (!boost::filesystem::is_directory(path))
338  return std::make_pair(false, contents);
339 
340  for (auto it = boost::filesystem::directory_iterator(path); it != boost::filesystem::directory_iterator();
341  ++it)
342  contents.emplace_back(expandPath(it->path()).string());
343 
344  return std::make_pair(true, contents);
345 }
T emplace_back(T... args)
T empty(T... args)
T make_pair(T... args)
std::string resolvePath(const std::string &path)
Resolves package:// URLs and relative file paths to their canonical form.

◆ loadAllFromFileToYAML()

std::pair< bool, std::vector< YAML::Node > > robowflex::IO::loadAllFromFileToYAML ( const std::string path)

Loads a file with multiple documents to a vector of YAML nodes.

Parameters
[in]pathFile to load.
Returns
A pair, where the first is true on success false on failure, and second is the vector of YAML nodes.

Definition at line 250 of file robowflex_library/src/io.cpp.

251 {
253  const std::string full_path = resolvePath(path);
254  if (full_path.empty())
255  return std::make_pair(false, file);
256 
257  if (!isExtension(full_path, "yml") && !isExtension(full_path, "yaml"))
258  return std::make_pair(false, file);
259 
260  try
261  {
262  return std::make_pair(true, YAML::LoadAllFromFile(full_path));
263  }
264  catch (std::exception &e)
265  {
266  return std::make_pair(false, file);
267  }
268 }

◆ loadFileToString()

std::string robowflex::IO::loadFileToString ( const std::string path)

Loads a file to a string.

Parameters
[in]pathFile to load.
Returns
The loaded file, or "" on failure (file does not exist).

Definition at line 164 of file robowflex_library/src/io.cpp.

165 {
166  const std::string full_path = resolvePath(path);
167  if (full_path.empty())
168  return "";
169 
170  std::ifstream ifs(full_path.c_str(), std::ios::in | std::ios::binary | std::ios::ate);
171 
172  std::ifstream::pos_type size = ifs.tellg();
173  ifs.seekg(0, std::ios::beg);
174 
175  std::vector<char> bytes(size);
176  ifs.read(bytes.data(), size);
177 
178  return std::string(bytes.data(), size);
179 }
T c_str(T... args)

◆ loadFileToYAML()

std::pair< bool, YAML::Node > robowflex::IO::loadFileToYAML ( const std::string path)

Loads a file to a YAML node.

Parameters
[in]pathFile to load.
Returns
A pair, where the first is true on success false on failure, and second is the YAML node.

Definition at line 230 of file robowflex_library/src/io.cpp.

231 {
232  YAML::Node file;
233  const std::string full_path = resolvePath(path);
234  if (full_path.empty())
235  return std::make_pair(false, file);
236 
237  if (!isExtension(full_path, "yml") && !isExtension(full_path, "yaml"))
238  return std::make_pair(false, file);
239 
240  try
241  {
242  return std::make_pair(true, YAML::LoadFile(full_path));
243  }
244  catch (std::exception &e)
245  {
246  return std::make_pair(false, file);
247  }
248 }

◆ loadXacroToString()

std::string robowflex::IO::loadXacroToString ( const std::string path)

Loads a .xacro file to a string.

Parameters
[in]pathFile to load.
Returns
The loaded file, or "" on failure (file does not exist or .xacro is malformed).

Definition at line 201 of file robowflex_library/src/io.cpp.

202 {
203  const std::string full_path = resolvePath(path);
204  if (full_path.empty())
205  return "";
206 
207  std::string cmd = "rosrun xacro xacro ";
208 
209 #if ROBOWFLEX_AT_LEAST_MELODIC
210 #else
211  cmd += "--inorder ";
212 #endif
213 
214  cmd += full_path;
215  return runCommand(cmd);
216 }
std::string runCommand(const std::string &cmd)
Runs a command cmd and returns stdout as a string.

◆ loadXMLToString()

std::string robowflex::IO::loadXMLToString ( const std::string path)

Loads an XML or .xacro file to a string.

Parameters
[in]pathFile to load.
Returns
The loaded file, or "" on failure (file does not exist or .xacro is malformed).

Definition at line 218 of file robowflex_library/src/io.cpp.

219 {
220  const std::string full_path = resolvePath(path);
221  if (full_path.empty())
222  return "";
223 
224  if (isExtension(full_path, "xacro"))
225  return loadXacroToString(full_path);
226 
227  return loadFileToString(full_path);
228 }
std::string loadFileToString(const std::string &path)
Loads a file to a string.
std::string loadXacroToString(const std::string &path)
Loads a .xacro file to a string.

◆ makeFilepath()

std::string robowflex::IO::makeFilepath ( const std::string directory,
const std::string filename 
)

Concatenates two elements of a path, a directory and a filename.

Parameters
[in]directoryPath to use as directory. If there are other elements at the end of the directory path, they will be removed.
[in]filenameFilename to add.
Returns
The canonical path for this path.

Definition at line 156 of file robowflex_library/src/io.cpp.

157 {
158  boost::filesystem::path dirpath = resolveParent(directory);
159  dirpath /= filename;
160 
161  return dirpath.string();
162 }
std::string resolveParent(const std::string &path)
Resolves package:// URLs to get the directory this path is in.

◆ messageToYAMLFile()

template<typename T >
bool robowflex::IO::messageToYAMLFile ( T &  msg,
const std::string file 
)

Dump a message (or YAML convertable object) to a file.

Parameters
[in]msgMessage to dump.
[in]fileFile to dump message to.
Template Parameters
TType of the message.
Returns
True on success, false on failure.

Definition at line 176 of file robowflex_library/include/robowflex_library/io.h.

177  {
178  YAML::Node yaml;
179  yaml = msg;
180 
181  return YAMLToFile(yaml, file);
182  }
bool YAMLToFile(const YAML::Node &node, const std::string &file)
Write the contents of a YAML node out to a potentially new file.

◆ poseFromNode()

geometry_msgs::Pose robowflex::IO::poseFromNode ( const YAML::Node &  node)

Converts a pose YAML to a goemetry message.

Parameters
[in]nodeNode to convert.
Returns
The converted message.

Definition at line 1881 of file yaml.cpp.

1882  {
1883  return node.as<geometry_msgs::Pose>();
1884  }

◆ resolvePackage()

std::string robowflex::IO::resolvePackage ( const std::string path)

Resolves package:// URLs to their canonical form. The path does not need to exist, but the package does. Can be used to write new files in packages.

Parameters
[in]pathPath to resolve.
Returns
The canonical path, or "" on failure.

Definition at line 88 of file robowflex_library/src/io.cpp.

89 {
90  if (path.empty())
91  return "";
92 
93  const std::string prefix = "package://";
94 
95  boost::filesystem::path file;
96  if (isPrefix(prefix, path))
97  {
98  boost::filesystem::path subpath(path.substr(prefix.length(), path.length() - 1));
99  const std::string package_name = (*subpath.begin()).string();
100 
101  const std::string package = ros::package::getPath(package_name);
102  if (package.empty())
103  {
104  RBX_WARN("Package `%s` does not exist.", package_name);
105  return "";
106  }
107 
108  file = package;
109  for (auto it = ++subpath.begin(); it != subpath.end(); ++it)
110  file /= *it;
111  }
112  else
113  file = path;
114 
115  return expandPath(file).string();
116 }
#define RBX_WARN(fmt,...)
Output a warning logging message.
Definition: log.h:110
T length(T... args)
T substr(T... args)

◆ resolveParent()

std::string robowflex::IO::resolveParent ( const std::string path)

Resolves package:// URLs to get the directory this path is in.

Parameters
[in]pathPath to get the parent of.
Returns
The directory that this path is contained in, or "" on failure.

Definition at line 150 of file robowflex_library/src/io.cpp.

151 {
152  boost::filesystem::path file = resolvePackage(path);
153  return file.parent_path().string();
154 }
std::string resolvePackage(const std::string &path)
Resolves package:// URLs to their canonical form. The path does not need to exist,...

◆ resolvePath()

std::string robowflex::IO::resolvePath ( const std::string path)

Resolves package:// URLs and relative file paths to their canonical form.

Parameters
[in]pathPath to resolve.
Returns
The canonical path, or "" on failure.

Definition at line 137 of file robowflex_library/src/io.cpp.

138 {
139  boost::filesystem::path file = resolvePackage(path);
140 
141  if (!boost::filesystem::exists(file))
142  {
143  RBX_WARN("File `%s` does not exist.", path);
144  return "";
145  }
146 
147  return boost::filesystem::canonical(boost::filesystem::absolute(file)).string();
148 }

◆ robotStateFromNode()

moveit_msgs::RobotState robowflex::IO::robotStateFromNode ( const YAML::Node &  node)

Converts a robot state YAML to a robot_state message.

Parameters
[in]nodeNode to convert.
Returns
The converted message.

Definition at line 1869 of file yaml.cpp.

1870  {
1871  return node.as<moveit_msgs::RobotState>();
1872  }

◆ runCommand()

std::string robowflex::IO::runCommand ( const std::string cmd)

Runs a command cmd and returns stdout as a string.

Parameters
[in]cmdCommand to run.
Returns
Contents of stdout from cmd, or "" on failure.

Definition at line 181 of file robowflex_library/src/io.cpp.

182 {
183  std::array<char, 128> buffer;
184  std::string result;
185  std::shared_ptr<FILE> pipe(popen(cmd.c_str(), "r"), pclose);
186  if (!pipe)
187  {
188  RBX_ERROR("Failed to run command `%s`!", cmd);
189  return "";
190  }
191 
192  while (!feof(pipe.get()))
193  {
194  if (fgets(buffer.data(), 128, pipe.get()) != nullptr)
195  result += buffer.data();
196  }
197 
198  return result;
199 }
T data(T... args)
T feof(T... args)
T fgets(T... args)
#define RBX_ERROR(fmt,...)
Output a error logging message.
Definition: log.h:102

◆ threadSleep()

void robowflex::IO::threadSleep ( double  seconds)

Put the current thread to sleep for a desired amount of seconds.

Parameters
[in]secondsSeconds to sleep for.

Definition at line 373 of file robowflex_library/src/io.cpp.

374 {
375  std::this_thread::sleep_for(std::chrono::milliseconds(static_cast<long int>(seconds * 1000)));
376 }
T sleep_for(T... args)

◆ tokenize()

template<typename T >
template std::vector< double > robowflex::IO::tokenize ( const std::string string,
const std::string separators = " " 
)

Separates a string into casted tokens, based upon separators.

Template Parameters
Thetype of element to cast strings into.
Parameters
[in]stringString to tokenize.
[in]separatorsSeparators to split string on.
Returns
The tokenized string.

Definition at line 379 of file robowflex_library/src/io.cpp.

380 {
381  boost::char_separator<char> seps(separators.c_str());
382  boost::tokenizer<boost::char_separator<char>> tokenizer(s, seps);
383 
384  std::vector<T> values;
385  std::transform(tokenizer.begin(), tokenizer.end(), std::back_inserter(values),
386  [](const std::string &s) { return boost::lexical_cast<T>(s); });
387 
388  return std::vector<T>();
389 }
T back_inserter(T... args)
T transform(T... args)

◆ toNode() [1/5]

YAML::Node robowflex::IO::toNode ( const geometry_msgs::Pose &  msg)

Converts a pose message to YAML.

Parameters
[in]msgMessage to convert.
Returns
The converted message.

Definition at line 1874 of file yaml.cpp.

1875  {
1876  YAML::Node node;
1877  node = msg;
1878  return node;
1879  }

◆ toNode() [2/5]

YAML::Node robowflex::IO::toNode ( const moveit_msgs::MotionPlanRequest msg)

Converts a motion plan request to YAML.

Parameters
[in]msgMessage to convert.
Returns
The converted message.

Definition at line 1893 of file yaml.cpp.

1894  {
1895  YAML::Node node;
1896  node = msg;
1897  return node;
1898  }

◆ toNode() [3/5]

YAML::Node robowflex::IO::toNode ( const moveit_msgs::PlanningScene &  msg)

Converts a planning scene message to YAML.

Parameters
[in]msgMessage to convert.
Returns
The converted message.

Definition at line 1886 of file yaml.cpp.

1887  {
1888  YAML::Node node;
1889  node = msg;
1890  return node;
1891  }

◆ toNode() [4/5]

YAML::Node robowflex::IO::toNode ( const moveit_msgs::RobotState &  msg)

Converts a robot state to YAML.

Parameters
[in]msgMessage to convert.
Returns
The converted message.

Definition at line 1907 of file yaml.cpp.

1908  {
1909  YAML::Node node;
1910  node = msg;
1911  return node;
1912  }

◆ toNode() [5/5]

YAML::Node robowflex::IO::toNode ( const moveit_msgs::RobotTrajectory &  msg)

Converts a motion plan to YAML.

Parameters
[in]msgMessage to convert.
Returns
The converted message.

Definition at line 1900 of file yaml.cpp.

1901  {
1902  YAML::Node node;
1903  node = msg;
1904  return node;
1905  }

◆ YAMLFileToMessage()

template<typename T >
bool robowflex::IO::YAMLFileToMessage ( T &  msg,
const std::string file 
)

Load a message (or YAML convertable object) from a file.

Parameters
[out]msgMessage to load into.
[in]fileFile to load message from.
Template Parameters
TType of the message.
Returns
True on success, false on failure.

Definition at line 191 of file robowflex_library/include/robowflex_library/io.h.

192  {
193  const auto &result = IO::loadFileToYAML(file);
194  if (result.first)
195  msg = result.second.as<T>();
196 
197  return result.first;
198  }
std::pair< bool, YAML::Node > loadFileToYAML(const std::string &path)
Loads a file to a YAML node.

◆ YAMLToFile()

bool robowflex::IO::YAMLToFile ( const YAML::Node &  node,
const std::string file 
)

Write the contents of a YAML node out to a potentially new file.

Parameters
[in]nodeNode to write.
[in]fileFilename to open.
Returns
True on success, false otherwise.

Definition at line 270 of file robowflex_library/src/io.cpp.

271 {
272  YAML::Emitter out;
273  out << node;
274 
275  std::ofstream fout;
276  IO::createFile(fout, file);
277 
278  fout << out.c_str();
279  fout.close();
280 
281  return true;
282 }
T close(T... args)