rotation_invariant_objects_rotator.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/RotationInvariantObjectsRotator.hpp>
28 
29 
30 bool getNodeParameters(ros::NodeHandle nh, std::string& source_file, std::string& target_file, std::string& object_type, std::string& object_id,
31  std::vector<std::string>& rotation_invariant_types)
32 {
33  bool success = true;
34 
35  if (!nh.getParam("source", source_file) || source_file.empty())
36  {
37  ROS_INFO("Missing parameter: \"source\"");
38  success = false;
39  }
40  else
41  {
42  ROS_INFO_STREAM("source: " << source_file);
43  }
44 
45  if (!nh.getParam("target", target_file) || target_file.empty())
46  {
47  ROS_INFO("Missing parameter: \"target\"");
48  success = false;
49  }
50  else
51  {
52  ROS_INFO_STREAM("target: " << target_file);
53  }
54 
55  if (!nh.getParam("object_type", object_type))
56  {
57  ROS_INFO("Missing parameter: \"object_type\"");
58  success = false;
59  }
60  else
61  {
62  ROS_INFO_STREAM("object_type: " << object_type);
63  }
64 
65  if (!nh.getParam("object_id", object_id))
66  {
67  ROS_INFO("Missing parameter: \"object_id\"");
68  success = false;
69  }
70  else
71  {
72  ROS_INFO_STREAM("object_id: " << object_id);
73  }
74 
75  if (!nh.getParam("rotation_invariant_types", rotation_invariant_types) || rotation_invariant_types.empty())
76  {
77  ROS_INFO("Missing parameter: \"rotation_invariant_types\"");
78  success = false;
79  }
80  else
81  {
82  std::stringstream info;
83  info << "rotation_invariant_types:";
84  for (const std::string& types : rotation_invariant_types)
85  {
86  info << std::endl << "\t" << types;
87  }
88  ROS_INFO_STREAM(info.str());
89  }
90 
91 
92  return success;
93 }
94 
95 int main (int argc, char **argv)
96 {
97  //Usual ros node stuff
98  ros::init(argc, argv, "rotation_invariant_objects_rotator");
99  ros::NodeHandle nh("~");
100  ISM::RotationInvariantObjectsRotator rotator;
101 
102  std::string source_file;
103  std::string target_file;
104  std::string object_type;
105  std::string object_id;
106  std::vector<std::string> rotation_invariant_types;
107 
108  if(getNodeParameters(nh, source_file, target_file, object_type, object_id, rotation_invariant_types))
109  {
110  rotator.rotateRotationInvariantObjects(source_file, target_file, object_type, object_id, (object_type.empty() || object_id.empty()), rotation_invariant_types);
111  ROS_INFO("ROTATION COMPLETED!");
112  }
113  else
114  {
115  ROS_INFO("ROTATION ABORTED! Check launch-file for missing parameter.");
116  }
117 
118  return 0;
119 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
#define ROS_INFO(...)
bool getNodeParameters(ros::NodeHandle nh, std::string &source_file, std::string &target_file, std::string &object_type, std::string &object_id, std::vector< std::string > &rotation_invariant_types)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const


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