Robowflex
v0.1
Making MoveIt Easy
|
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::string > | findPackageURIs (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... | |
File and ROS Input / Output operations.
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.
[out] | out | Output stream to initialize. |
[in] | file | File to create and open. |
Definition at line 296 of file robowflex_library/src/io.cpp.
std::string robowflex::IO::createTempFile | ( | std::ofstream & | out | ) |
Creates a temporary file and opens an output stream.
[out] | out | Output stream to initialize. |
Definition at line 310 of file robowflex_library/src/io.cpp.
void robowflex::IO::deleteFile | ( | const std::string & | file | ) |
Deletes a file.
[in] | file | File to delete. |
Definition at line 319 of file robowflex_library/src/io.cpp.
std::set< std::string > robowflex::IO::findPackageURIs | ( | const std::string & | string | ) |
Finds all package URIs within a string.
[in] | string | String to search. |
Definition at line 118 of file robowflex_library/src/io.cpp.
bool robowflex::IO::fromYAMLFile | ( | moveit_msgs::MotionPlanRequest & | msg, |
const std::string & | file | ||
) |
Loads a motion planning request from a YAML file.
[out] | msg | Message to load into. |
[in] | file | File to load. |
Definition at line 1919 of file yaml.cpp.
bool robowflex::IO::fromYAMLFile | ( | moveit_msgs::PlanningScene & | msg, |
const std::string & | file | ||
) |
Loads a planning scene from a YAML file.
[out] | msg | Message to load into. |
[in] | file | File to load. |
bool robowflex::IO::fromYAMLFile | ( | moveit_msgs::RobotState & | msg, |
const std::string & | file | ||
) |
Loads a robot state from a YAML file.
[out] | msg | Message to load into. |
[in] | file | File to load. |
std::string robowflex::IO::generateUUID | ( | ) |
Generates a UUID.
Definition at line 284 of file robowflex_library/src/io.cpp.
boost::posix_time::ptime robowflex::IO::getDate | ( | ) |
Get the current time (up to milliseconds)
Definition at line 362 of file robowflex_library/src/io.cpp.
std::string robowflex::IO::getHostname | ( | ) |
Get the hostname of the system.
Definition at line 347 of file robowflex_library/src/io.cpp.
std::string robowflex::IO::getMessageMD5 | ( | T & | msg | ) |
Compute MD5 hash of message.
[in] | msg | Message to hash. |
T | Type of the message. |
Definition at line 206 of file robowflex_library/include/robowflex_library/io.h.
std::size_t robowflex::IO::getProcessID | ( | ) |
Get the process ID of this process.
Definition at line 352 of file robowflex_library/src/io.cpp.
double robowflex::IO::getSeconds | ( | boost::posix_time::ptime | start, |
boost::posix_time::ptime | finish | ||
) |
Get a duration in seconds from two times.
[in] | start | The start time. |
[in] | finish | The finish time. |
Definition at line 367 of file robowflex_library/src/io.cpp.
std::size_t robowflex::IO::getThreadID | ( | ) |
Get the thread ID of the current thread.
Definition at line 357 of file robowflex_library/src/io.cpp.
bool robowflex::IO::isNode | ( | const YAML::Node & | node | ) |
std::pair< bool, std::vector< std::string > > robowflex::IO::listDirectory | ( | const std::string & | directory | ) |
Lists of the contents of a directory.
[in] | directory | Directory to list. |
Definition at line 328 of file robowflex_library/src/io.cpp.
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.
[in] | path | File to load. |
Definition at line 250 of file robowflex_library/src/io.cpp.
std::string robowflex::IO::loadFileToString | ( | const std::string & | path | ) |
Loads a file to a string.
[in] | path | File to load. |
Definition at line 164 of file robowflex_library/src/io.cpp.
std::pair< bool, YAML::Node > robowflex::IO::loadFileToYAML | ( | const std::string & | path | ) |
Loads a file to a YAML node.
[in] | path | File to load. |
Definition at line 230 of file robowflex_library/src/io.cpp.
std::string robowflex::IO::loadXacroToString | ( | const std::string & | path | ) |
Loads a .xacro file to a string.
[in] | path | File to load. |
Definition at line 201 of file robowflex_library/src/io.cpp.
std::string robowflex::IO::loadXMLToString | ( | const std::string & | path | ) |
Loads an XML or .xacro file to a string.
[in] | path | File to load. |
Definition at line 218 of file robowflex_library/src/io.cpp.
std::string robowflex::IO::makeFilepath | ( | const std::string & | directory, |
const std::string & | filename | ||
) |
Concatenates two elements of a path, a directory and a filename.
[in] | directory | Path to use as directory. If there are other elements at the end of the directory path, they will be removed. |
[in] | filename | Filename to add. |
Definition at line 156 of file robowflex_library/src/io.cpp.
bool robowflex::IO::messageToYAMLFile | ( | T & | msg, |
const std::string & | file | ||
) |
Dump a message (or YAML convertable object) to a file.
[in] | msg | Message to dump. |
[in] | file | File to dump message to. |
T | Type of the message. |
Definition at line 176 of file robowflex_library/include/robowflex_library/io.h.
geometry_msgs::Pose robowflex::IO::poseFromNode | ( | const YAML::Node & | node | ) |
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.
[in] | path | Path to resolve. |
Definition at line 88 of file robowflex_library/src/io.cpp.
std::string robowflex::IO::resolveParent | ( | const std::string & | path | ) |
Resolves package://
URLs to get the directory this path is in.
[in] | path | Path to get the parent of. |
Definition at line 150 of file robowflex_library/src/io.cpp.
std::string robowflex::IO::resolvePath | ( | const std::string & | path | ) |
Resolves package://
URLs and relative file paths to their canonical form.
[in] | path | Path to resolve. |
Definition at line 137 of file robowflex_library/src/io.cpp.
moveit_msgs::RobotState robowflex::IO::robotStateFromNode | ( | const YAML::Node & | node | ) |
std::string robowflex::IO::runCommand | ( | const std::string & | cmd | ) |
Runs a command cmd and returns stdout as a string.
[in] | cmd | Command to run. |
Definition at line 181 of file robowflex_library/src/io.cpp.
void robowflex::IO::threadSleep | ( | double | seconds | ) |
Put the current thread to sleep for a desired amount of seconds.
[in] | seconds | Seconds to sleep for. |
Definition at line 373 of file robowflex_library/src/io.cpp.
template std::vector< double > robowflex::IO::tokenize | ( | const std::string & | string, |
const std::string & | separators = " " |
||
) |
Separates a string into casted tokens, based upon separators.
The | type of element to cast strings into. |
[in] | string | String to tokenize. |
[in] | separators | Separators to split string on. |
Definition at line 379 of file robowflex_library/src/io.cpp.
YAML::Node robowflex::IO::toNode | ( | const geometry_msgs::Pose & | msg | ) |
YAML::Node robowflex::IO::toNode | ( | const moveit_msgs::MotionPlanRequest & | msg | ) |
YAML::Node robowflex::IO::toNode | ( | const moveit_msgs::PlanningScene & | msg | ) |
YAML::Node robowflex::IO::toNode | ( | const moveit_msgs::RobotState & | msg | ) |
YAML::Node robowflex::IO::toNode | ( | const moveit_msgs::RobotTrajectory & | msg | ) |
bool robowflex::IO::YAMLFileToMessage | ( | T & | msg, |
const std::string & | file | ||
) |
Load a message (or YAML convertable object) from a file.
[out] | msg | Message to load into. |
[in] | file | File to load message from. |
T | Type of the message. |
Definition at line 191 of file robowflex_library/include/robowflex_library/io.h.
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.
[in] | node | Node to write. |
[in] | file | Filename to open. |
Definition at line 270 of file robowflex_library/src/io.cpp.