data_merger.cpp
Go to the documentation of this file.
1 
18 //Global includes
19 
20 
21 
22 //Pkg includes
23 #include <ros/ros.h>
24 
25 
26 //ISM includes
27 #include <ISM/tools/DataMerger.hpp>
28 
29 
30 bool getNodeParameters(ros::NodeHandle nh, std::string& target_file, std::vector<std::string>& source_files, bool& merge_records, bool& merge_models)
31 {
32  bool success = true;
33 
34  if (!nh.getParam("target", target_file) || target_file.empty())
35  {
36  ROS_INFO("Missing parameter: \"target\"");
37  success = false;
38  }
39  else
40  {
41  ROS_INFO_STREAM("target: " << target_file);
42  }
43 
44  if (!nh.getParam("sources", source_files) || source_files.empty())
45  {
46  ROS_INFO("Missing parameter: \"sources\"");
47  success = false;
48  }
49  else
50  {
51  std::stringstream info;
52  info << "sources:";
53  for (const std::string& file : source_files)
54  {
55  info << std::endl << "\t" << file;
56  }
57  ROS_INFO_STREAM(info.str());
58  }
59 
60  if (!nh.getParam("merge_records", merge_records))
61  {
62  ROS_INFO("Missing parameter: \"merge_records\"");
63  success = false;
64  }
65  else
66  {
67  ROS_INFO_STREAM("merge_records: " << merge_records);
68  }
69 
70  if (!nh.getParam("merge_models", merge_models))
71  {
72  ROS_INFO("Missing parameter: \"merge_models\"");
73  success = false;
74  }
75  else
76  {
77  ROS_INFO_STREAM("merge_models: " << merge_models);
78  }
79 
80 
81  return success;
82 }
83 
84 int main (int argc, char **argv)
85 {
86  //Usual ros node stuff
87  ros::init(argc, argv, "data_merger");
88  ros::NodeHandle nh("~");
89  ISM::DataMerger data_merger;
90 
91  std::string target_file;
92  std::vector<std::string> source_files;
93  bool merge_records;
94  bool merge_models;
95 
96  if(getNodeParameters(nh, target_file, source_files, merge_records, merge_models))
97  {
98  data_merger.merge(target_file, source_files, merge_records, merge_models);
99  ROS_INFO("MERGE COMPLETED!");
100  }
101  else
102  {
103  ROS_INFO("MERGE ABORTED! Check launch-file for missing parameter.");
104  }
105 
106  return 0;
107 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Definition: data_merger.cpp:84
#define ROS_INFO(...)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
bool getNodeParameters(ros::NodeHandle nh, std::string &target_file, std::vector< std::string > &source_files, bool &merge_records, bool &merge_models)
Definition: data_merger.cpp:30


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