27 #include <ISM/tools/RotationInvariantObjectsRotator.hpp> 31 std::vector<std::string>& rotation_invariant_types)
35 if (!nh.
getParam(
"source", source_file) || source_file.empty())
37 ROS_INFO(
"Missing parameter: \"source\"");
45 if (!nh.
getParam(
"target", target_file) || target_file.empty())
47 ROS_INFO(
"Missing parameter: \"target\"");
55 if (!nh.
getParam(
"object_type", object_type))
57 ROS_INFO(
"Missing parameter: \"object_type\"");
65 if (!nh.
getParam(
"object_id", object_id))
67 ROS_INFO(
"Missing parameter: \"object_id\"");
75 if (!nh.
getParam(
"rotation_invariant_types", rotation_invariant_types) || rotation_invariant_types.empty())
77 ROS_INFO(
"Missing parameter: \"rotation_invariant_types\"");
82 std::stringstream info;
83 info <<
"rotation_invariant_types:";
84 for (
const std::string& types : rotation_invariant_types)
86 info << std::endl <<
"\t" << types;
95 int main (
int argc,
char **argv)
98 ros::init(argc, argv,
"rotation_invariant_objects_rotator");
100 ISM::RotationInvariantObjectsRotator rotator;
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;
108 if(
getNodeParameters(nh, source_file, target_file, object_type, object_id, rotation_invariant_types))
110 rotator.rotateRotationInvariantObjects(source_file, target_file, object_type, object_id, (object_type.empty() || object_id.empty()), rotation_invariant_types);
115 ROS_INFO(
"ROTATION ABORTED! Check launch-file for missing parameter.");
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
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