Robowflex  v0.1
Making MoveIt Easy
tapedeck.cpp File Reference
#include <boost/date_time.hpp>
#include <robowflex_library/log.h>
#include <robowflex_library/util.h>
#include <robowflex_movegroup/services.h>

Go to the source code of this file.

Functions

void callback (movegroup::MoveGroupHelper::Action &action)
 
int main (int argc, char **argv)
 

Function Documentation

◆ callback()

void callback ( movegroup::MoveGroupHelper::Action action)

Definition at line 20 of file tapedeck.cpp.

21 {
22  ros::Time time = ros::Time::now();
23 
24  // Save the requests to a folder in the home directory.
25  const std::string filename = "~/robowflex_tapedeck/" + to_iso_string(time.toBoost()) + ".yml";
26  action.toYAMLFile(filename);
27 
28  RBX_INFO("Wrote YAML for Request ID `%s` to file `%s`", action.id, filename);
29 }
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118
bool toYAMLFile(const std::string &filename)
Save a recorded action to a YAML file.
Definition: services.cpp:46
T time(T... args)

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 31 of file tapedeck.cpp.

32 {
33  // Startup ROS
34  ROS ros(argc, argv);
35 
36  // Create helper
38 
39  // Setup callback function
41 
42  // Wait until killed
43  ros.wait();
44 }
RAII-pattern for starting up ROS.
Definition: util.h:52
A helper class that allows for pulling and pushing of scenes, robots, and trajectories to move group.
Definition: services.h:27
void setResultCallback(const ResultCallback &callback)
Sets a callback function that is called whenever a motion plan request is serviced by move group.
Definition: services.cpp:107
void callback(movegroup::MoveGroupHelper::Action &action)
Definition: tapedeck.cpp:20