poseInterpolator.cpp
Go to the documentation of this file.
1 
19 #include <string>
20 #include <vector>
21 #include <algorithm>
22 #include <set>
23 #include <boost/program_options.hpp>
24 #include <fstream>
25 /*
26  * Command line tool to interpolate poses between between objects in a given database.
27  *
28  * Usage:
29  * ./poseInterpolator -s <path-to-source-file> -t <path-to-target-file> -n <steps-number-of-interpolation>
30  *
31  */
32 using namespace ISM;
33 using namespace std;
34 namespace po = boost::program_options;
35 
36 
37 int main (int argc, char** argv) {
38  po::options_description desc("Allowed options");
39  desc.add_options()
40  ("help,h", "produce help message")
41  ;
42  po::options_description required("Required");
43  required.add_options()
44  ("source-file,s", po::value<string>(), "source file")
45  ("target-file,t", po::value<string>(), "target file")
46  ("steps-number,n", po::value<int>(), "steps number")
47  ;
48 
49  desc.add(required);
50 
51  po::variables_map vm;
52  po::store(po::parse_command_line(argc, argv, desc), vm);
53  po::notify(vm);
54  int stepsNumber = vm["steps-number"].as<int>();
55 
56 
57  if (vm.count("help") || !vm.count("target-file") || !vm.count("source-file") || !vm.count("steps-number")) {
58  cout << desc << "\n";
59  return 1;
60  }
61 
62  string sourceFile = vm["source-file"].as<string>();
63  string targetFile = vm["target-file"].as<string>();
64 
65  //actual interpolation process
66  PoseInterpolator pose_interpolator;
67  pose_interpolator.interpolate(sourceFile, targetFile, stepsNumber);
68 }
void interpolate(const std::string &sourceFile, const std::string &targetFile, int stepNumber)
int main(int argc, char **argv)
this namespace contains all generally usable classes.


asr_lib_ism
Author(s): Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel
autogenerated on Wed Jan 8 2020 04:02:40