Robowflex  v0.1
Making MoveIt Easy
robowflex_library/include/robowflex_library/io.h
Go to the documentation of this file.
1 /* Author: Zachary Kingston */
2 
3 #ifndef ROBOWFLEX_IO_
4 #define ROBOWFLEX_IO_
5 
6 #include <string> // for std::string
7 #include <utility> // for std::pair
8 #include <fstream> // for std::ofstream
9 
10 #include <boost/date_time.hpp> // for date operations
11 
12 #include <ros/message_traits.h> // for message operations
13 
14 #include <yaml-cpp/yaml.h> // for YAML parsing
15 
16 namespace robowflex
17 {
18  /** \brief File and ROS Input / Output operations.
19  */
20  namespace IO
21  {
22  /** \brief Generates a UUID.
23  * \return String of UUID.
24  */
26 
27  /** \brief Resolves `package://` URLs to their canonical form.
28  * The path does not need to exist, but the package does. Can be used to write new files in packages.
29  * \param[in] path Path to resolve.
30  * \return The canonical path, or "" on failure.
31  */
33 
34  /** \brief Finds all package URIs within a string.
35  * \param[in] string String to search.
36  * \return List of package URIs.
37  */
39 
40  /** \brief Resolves `package://` URLs and relative file paths to their canonical form.
41  * \param[in] path Path to resolve.
42  * \return The canonical path, or "" on failure.
43  */
44  std::string resolvePath(const std::string &path);
45 
46  /** \brief Resolves `package://` URLs to get the directory this path is in.
47  * \param[in] path Path to get the parent of.
48  * \return The directory that this path is contained in, or "" on failure.
49  */
51 
52  /** \brief Concatenates two elements of a path, a directory and a filename.
53  * \param[in] directory Path to use as directory. If there are other elements at the end of the
54  * directory path, they will be removed.
55  * \param[in] filename Filename to add.
56  * \return The canonical path for this path.
57  */
58  std::string makeFilepath(const std::string &directory, const std::string &filename);
59 
60  /** \brief Loads an XML or .xacro file to a string.
61  * \param[in] path File to load.
62  * \return The loaded file, or "" on failure (file does not exist or .xacro is malformed).
63  */
65 
66  /** \brief Loads a .xacro file to a string.
67  * \param[in] path File to load.
68  * \return The loaded file, or "" on failure (file does not exist or .xacro is malformed).
69  */
71 
72  /** \brief Loads a file to a string.
73  * \param[in] path File to load.
74  * \return The loaded file, or "" on failure (file does not exist).
75  */
77 
78  /** \brief Runs a command \a cmd and returns stdout as a string.
79  * \param[in] cmd Command to run.
80  * \return Contents of stdout from \a cmd, or "" on failure.
81  */
83 
84  /** \brief Loads a file to a YAML node.
85  * \param[in] path File to load.
86  * \return A pair, where the first is true on success false on failure, and second is the YAML node.
87  */
89 
90  /** \brief Loads a file with multiple documents to a vector of YAML nodes.
91  * \param[in] path File to load.
92  * \return A pair, where the first is true on success false on failure, and second is the vector of
93  * YAML nodes.
94  */
96 
97  /** \brief Creates a file and opens an output stream. Creates directories if they do not exist.
98  * \param[out] out Output stream to initialize.
99  * \param[in] file File to create and open.
100  */
101  void createFile(std::ofstream &out, const std::string &file);
102 
103  /** \brief Creates a temporary file and opens an output stream.
104  * \param[out] out Output stream to initialize.
105  * \return Filename of temporary file.
106  */
108 
109  /** \brief Deletes a file.
110  * \param[in] file File to delete.
111  */
112  void deleteFile(const std::string &file);
113 
114  /** \brief Lists of the contents of a directory.
115  * \param[in] directory Directory to list.
116  * \return A pair of a bool and a vector of strings of filenames of the directories contents. The
117  * first element will be true on success, false on failure. These filenames are absolute paths.
118  */
120 
121  /** \brief Get the hostname of the system.
122  * \return String of the hostname.
123  */
125 
126  /** \brief Get the process ID of this process.
127  * \return The process ID.
128  */
130 
131  /** \brief Get the thread ID of the current thread.
132  * \return The thread ID.
133  */
135 
136  /** \brief Get the current time (up to milliseconds)
137  * \return The time.
138  */
139  boost::posix_time::ptime getDate();
140 
141  /** \brief Get a duration in seconds from two times.
142  * \param[in] start The start time.
143  * \param[in] finish The finish time.
144  * \return The time in seconds.
145  */
146  double getSeconds(boost::posix_time::ptime start, boost::posix_time::ptime finish);
147 
148  /** \brief Put the current thread to sleep for a desired amount of seconds.
149  * \param[in] seconds Seconds to sleep for.
150  */
151  void threadSleep(double seconds);
152 
153  /** \brief Separates a \a string into casted tokens, based upon \a separators.
154  * \tparam The type of element to cast strings into.
155  * \param[in] string String to tokenize.
156  * \param[in] separators Separators to split string on.
157  * \return The tokenized string.
158  */
159  template <typename T>
160  std::vector<T> tokenize(const std::string &string, const std::string &separators = " ");
161 
162  /** \brief Write the contents of a YAML node out to a potentially new file.
163  * \param[in] node Node to write.
164  * \param[in] file Filename to open.
165  * \return True on success, false otherwise.
166  */
167  bool YAMLToFile(const YAML::Node &node, const std::string &file);
168 
169  /** \brief Dump a message (or YAML convertable object) to a file.
170  * \param[in] msg Message to dump.
171  * \param[in] file File to dump message to.
172  * \tparam T Type of the message.
173  * \return True on success, false on failure.
174  */
175  template <typename T>
176  bool messageToYAMLFile(T &msg, const std::string &file)
177  {
178  YAML::Node yaml;
179  yaml = msg;
180 
181  return YAMLToFile(yaml, file);
182  }
183 
184  /** \brief Load a message (or YAML convertable object) from a file.
185  * \param[out] msg Message to load into.
186  * \param[in] file File to load message from.
187  * \tparam T Type of the message.
188  * \return True on success, false on failure.
189  */
190  template <typename T>
191  bool YAMLFileToMessage(T &msg, const std::string &file)
192  {
193  const auto &result = IO::loadFileToYAML(file);
194  if (result.first)
195  msg = result.second.as<T>();
196 
197  return result.first;
198  }
199 
200  /** \brief Compute MD5 hash of message.
201  * \param[in] msg Message to hash.
202  * \tparam T Type of the message.
203  * \return The hash of the message.
204  */
205  template <typename T>
207  {
208  return ros::message_traits::md5sum<T>(msg);
209  }
210  } // namespace IO
211 } // namespace robowflex
212 
213 #endif
bool YAMLToFile(const YAML::Node &node, const std::string &file)
Write the contents of a YAML node out to a potentially new file.
double getSeconds(boost::posix_time::ptime start, boost::posix_time::ptime finish)
Get a duration in seconds from two times.
std::string resolveParent(const std::string &path)
Resolves package:// URLs to get the directory this path is in.
std::set< std::string > findPackageURIs(const std::string &string)
Finds all package URIs within a string.
boost::posix_time::ptime getDate()
Get the current time (up to milliseconds)
std::string resolvePackage(const std::string &path)
Resolves package:// URLs to their canonical form. The path does not need to exist,...
void deleteFile(const std::string &file)
Deletes a file.
std::size_t getProcessID()
Get the process ID of this process.
std::pair< bool, std::vector< YAML::Node > > loadAllFromFileToYAML(const std::string &path)
Loads a file with multiple documents to a vector of YAML nodes.
std::pair< bool, YAML::Node > loadFileToYAML(const std::string &path)
Loads a file to a YAML node.
std::string makeFilepath(const std::string &directory, const std::string &filename)
Concatenates two elements of a path, a directory and a filename.
std::string runCommand(const std::string &cmd)
Runs a command cmd and returns stdout as a string.
std::string getHostname()
Get the hostname of the system.
std::string getMessageMD5(T &msg)
Compute MD5 hash of message.
std::pair< bool, std::vector< std::string > > listDirectory(const std::string &directory)
Lists of the contents of a directory.
std::vector< T > tokenize(const std::string &string, const std::string &separators=" ")
Separates a string into casted tokens, based upon separators.
std::string loadFileToString(const std::string &path)
Loads a file to a string.
std::string generateUUID()
Generates a UUID.
std::size_t getThreadID()
Get the thread ID of the current thread.
std::string createTempFile(std::ofstream &out)
Creates a temporary file and opens an output stream.
std::string resolvePath(const std::string &path)
Resolves package:// URLs and relative file paths to their canonical form.
bool messageToYAMLFile(T &msg, const std::string &file)
Dump a message (or YAML convertable object) to a file.
std::string loadXMLToString(const std::string &path)
Loads an XML or .xacro file to a string.
void createFile(std::ofstream &out, const std::string &file)
Creates a file and opens an output stream. Creates directories if they do not exist.
std::string loadXacroToString(const std::string &path)
Loads a .xacro file to a string.
void threadSleep(double seconds)
Put the current thread to sleep for a desired amount of seconds.
bool YAMLFileToMessage(T &msg, const std::string &file)
Load a message (or YAML convertable object) from a file.
Main namespace. Contains all library classes and functions.
Definition: scene.cpp:25