Aikido
DetectedObject.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PERCEPTION_DETECTEDOBJECT_HPP_
2 #define AIKIDO_PERCEPTION_DETECTEDOBJECT_HPP_
3 
4 #include <string>
5 
6 #include <dart/dart.hpp>
7 
8 #include "aikido/io/yaml.hpp"
9 
10 namespace aikido {
11 namespace perception {
12 
15 
22 
35 
40 
42 {
43 public:
45  DetectedObject() = default;
46 
55  const std::string& objectName,
56  const int& objectId,
57  const std::string& detectionFrameID,
58  const std::string& yamlStr);
59 
60  virtual ~DetectedObject() = default;
61 
63  std::string getUid() const;
64 
66  std::string getAssetKey() const;
67 
69  std::string getDetectionFrameID() const;
70 
72  std::string getName() const;
73 
75  YAML::Node getYamlNode();
76 
78  dart::dynamics::MetaSkeletonPtr getMetaSkeleton() const;
79 
81  void setMetaSkeleton(const dart::dynamics::MetaSkeletonPtr& metaSkeleton);
82 
90  template <typename T>
91  T getInfoByKey(const std::string& key) const;
92 
93 private:
95  std::string mObjectName;
96 
98  std::string mUid;
99 
101  std::string mAssetKey;
102 
104  std::string mDetectionFrameID;
105 
107  YAML::Node mYamlNode;
108 
110  dart::dynamics::MetaSkeletonPtr mMetaSkeleton;
111 };
112 
113 } // namespace perception
114 } // namespace aikido
115 
117 
118 #endif // AIKIDO_PERCEPTION_DETECTEDOBJECT_HPP_
aikido::perception::DetectedObject::getYamlNode
YAML::Node getYamlNode()
Get the map of keys to additional informations.
aikido::perception::DetectedObject::getAssetKey
std::string getAssetKey() const
Get the object key for AssetDatabase.
aikido::perception::DetectedObject::mObjectName
std::string mObjectName
The name of the object.
Definition: DetectedObject.hpp:95
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::perception::DetectedObject::setMetaSkeleton
void setMetaSkeleton(const dart::dynamics::MetaSkeletonPtr &metaSkeleton)
Set Metaskeleton.
aikido::perception::DetectedObject::getName
std::string getName() const
Get the name of this object.
aikido::perception::DetectedObject::mDetectionFrameID
std::string mDetectionFrameID
The detection frame id that refers the origin of this object's pose.
Definition: DetectedObject.hpp:104
DetectedObject-impl.hpp
aikido::perception::DetectedObject::getUid
std::string getUid() const
Get the unique id of the object.
aikido::perception::DetectedObject::~DetectedObject
virtual ~DetectedObject()=default
aikido::perception::DetectedObject::mAssetKey
std::string mAssetKey
The object key for AssetDatabase.
Definition: DetectedObject.hpp:101
yaml.hpp
aikido::perception::DetectedObject::mUid
std::string mUid
The unique id of the object.
Definition: DetectedObject.hpp:98
aikido::perception::DetectedObject::getDetectionFrameID
std::string getDetectionFrameID() const
Get the detection frame id that refers the origin of this object's pose.
aikido::perception::DetectedObject::mMetaSkeleton
dart::dynamics::MetaSkeletonPtr mMetaSkeleton
MetaSkeleton associated with this object.
Definition: DetectedObject.hpp:110
aikido::perception::DetectedObject::getInfoByKey
T getInfoByKey(const std::string &key) const
Get a specific value from the information map by a key and the typename of the field.
Definition: DetectedObject-impl.hpp:8
aikido::perception::DetectedObject
DetectedObject delegates a detected object from a third-party perception algorithm.
Definition: DetectedObject.hpp:41
aikido::perception::DetectedObject::DetectedObject
DetectedObject()=default
Default constructor.
aikido::perception::DetectedObject::mYamlNode
YAML::Node mYamlNode
The information map with additional information of this object.
Definition: DetectedObject.hpp:107
aikido::perception::DetectedObject::getMetaSkeleton
dart::dynamics::MetaSkeletonPtr getMetaSkeleton() const
Get the metaSkeleton associated with this object.