ObjectDatabaseEntry.h
Go to the documentation of this file.
1 
21 #ifndef OBJECT_DATABASE_ENTRY_H_
22 #define OBJECT_DATABASE_ENTRY_H_
23 
24 #include <boost/filesystem.hpp>
25 #include <string>
26 #include <geometry_msgs/Point.h>
27 #include <geometry_msgs/Pose.h>
29 
30 namespace object_database
31 {
32 namespace fs = boost::filesystem;
33 
39 {
40 public:
49  const fs::path path, const fs::path rvizMeshResourcePath,
50  const fs::path normalVectorResourcePath);
51  ObjectDatabaseEntry(ObjectDatabaseRecognizer *recognizerPtr, const std::string uniqueName,
52  const fs::path path, const fs::path rvizMeshResourcePath,
53  const fs::path normalVectorResourcePath, const fs::path getDeviationResourcePath,
54  const fs::path rotation_invariance_resource_path);
55 
56  // dtor
58  { }
59 
64 
68  const std::string getUniqueName();
69 
73  const fs::path getPath();
74 
78  const fs::path getRvizMeshResourcePath();
79 
83  const fs::path getNormalVectorResourcePath();
84 
85  std::vector<geometry_msgs::Point> getNormalVectors();
86 
87  fs::path getDeviationResourcePath() const;
88 
89  std::vector<double> getDeviationsFromFile();
90 
91 
92  fs::path getRotationInvarianceResourcePath() const;
93 
97  const bool getRotationInvarianceFromFile();
98 
99 private:
104 
109 
113  fs::path mPath;
114 
119 
124 
129 
134 
135  std::vector<geometry_msgs::Point> mNormalVectors;
136  std::vector<double> deviations_;
138 };
139 }
140 
141 #endif
ROS_DEPRECATED ObjectDatabaseEntry(ObjectDatabaseRecognizer *recognizerPtr, const std::string uniqueName, const fs::path path, const fs::path rvizMeshResourcePath, const fs::path normalVectorResourcePath)
std::vector< geometry_msgs::Point > getNormalVectors()
ObjectDatabaseRecognizer * getRecognizer()
#define ROS_DEPRECATED
::xsd::cxx::tree::string< char, simple_type > string
ObjectDatabaseRecognizer * mRecognizerPtr
std::vector< geometry_msgs::Point > mNormalVectors


asr_object_database
Author(s): Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Braun Kai, Heizmann Heinrich, Heller Florian, Kasper Alexander, Marek Felix, Mehlhaus Jonas, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Walter Milena
autogenerated on Wed Jan 8 2020 03:12:13