recorder.cpp
Go to the documentation of this file.
1 
18 // Global includes
19 #include <string>
20 
21 // ROS includes
22 #include <ros/ros.h>
23 
24 // ISM includes
25 #include <ISM/recorder/Recorder.hpp>
26 #include <ISM/utility/Util.hpp>
27 
28 // Local includes
30 
31 
32 class Recorder
33 {
34  public:
35  Recorder() : nh_("~")
36  {
37  std::string db_filename;
38  getNodeParameters(db_filename);
39 
40  ism_recorder_ = ISM::RecorderPtr(new ISM::Recorder(db_filename));
41  }
42 
43 
44  void recordObjects(ISM::ObjectSetPtr object_set)
45  {
46  ISM::printYellow("Record object set:\n");
47 
48  ism_recorder_->insert(object_set, scene_name_);
49 
50  return;
51  }
52 
53 
54  private:
56  ISM::RecorderPtr ism_recorder_;
57  std::string scene_name_;
58 
59 
60  void getNodeParameters(std::string& db_filename)
61  {
62  if (!nh_.getParam("sceneName", scene_name_))
63  {
64  scene_name_ = "scene";
65  }
66  ROS_INFO_STREAM("sceneName: " << scene_name_);
67 
68 
69  if (!nh_.getParam("dbfilename", db_filename))
70  {
71  db_filename = "/tmp/record.sqlite";
72  ISM::printGreen("No database path specified. Default path \"" + db_filename + "\" will be used.\n");
73  }
74  ROS_INFO_STREAM("dbfilename: " << db_filename);
75  }
76 };
77 
78 int main (int argc, char **argv)
79 {
80  //Usual ros node stuff
81  ros::init(argc, argv, "recorder");
82  Recorder* recorder = new Recorder();
83  SceneConfigurator* scene_configurator = new SceneConfigurator(boost::bind(&Recorder::recordObjects, recorder, _1));
84 
85  ros::spin();
86 
87  //clean after shutdown
88  delete scene_configurator;
89  delete recorder;
90 
91 
92  return 0;
93 }
ISM::RecorderPtr ism_recorder_
Definition: recorder.cpp:56
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Recorder()
Definition: recorder.cpp:35
int main(int argc, char **argv)
Definition: recorder.cpp:78
ROSCPP_DECL void spin(Spinner &spinner)
void recordObjects(ISM::ObjectSetPtr object_set)
Definition: recorder.cpp:44
ros::NodeHandle nh_
Definition: recorder.cpp:55
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
void getNodeParameters(std::string &db_filename)
Definition: recorder.cpp:60
std::string scene_name_
Definition: recorder.cpp:57


asr_ism
Author(s): Borella Jocelyn, Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel
autogenerated on Thu Jan 9 2020 07:20:58