Public Member Functions | Private Attributes
object_database::ObjectDatabaseEntry Class Reference

#include <ObjectDatabaseEntry.h>

List of all members.

Public Member Functions

fs::path getDeviationResourcePath () const
std::vector< double > getDeviationsFromFile ()
const fs::path getNormalVectorResourcePath ()
std::vector< geometry_msgs::Point > getNormalVectors ()
const fs::path getPath ()
ObjectDatabaseRecognizergetRecognizer ()
const bool getRotationInvarianceFromFile ()
fs::path getRotationInvarianceResourcePath () const
const fs::path getRvizMeshResourcePath ()
const std::string getUniqueName ()
ROS_DEPRECATED ObjectDatabaseEntry (ObjectDatabaseRecognizer *recognizerPtr, const std::string uniqueName, const fs::path path, const fs::path rvizMeshResourcePath, const fs::path normalVectorResourcePath)
 ObjectDatabaseEntry (ObjectDatabaseRecognizer *recognizerPtr, const std::string uniqueName, const fs::path path, const fs::path rvizMeshResourcePath, const fs::path normalVectorResourcePath, const fs::path getDeviationResourcePath, const fs::path rotation_invariance_resource_path)
virtual ~ObjectDatabaseEntry ()

Private Attributes

fs::path deviation_resource_path_
std::vector< double > deviations_
fs::path mNormalVectorResourcePath
std::vector< geometry_msgs::Point > mNormalVectors
fs::path mPath
ObjectDatabaseRecognizermRecognizerPtr
fs::path mRvizMeshResourcePath
std::string mUniqueName
fs::path rotation_invariance_resource_path
bool rotation_invariant

Detailed Description

The class 'ObjectDatabaseEntry' contains all information about an entry in the object database.

Definition at line 38 of file ObjectDatabaseEntry.h.


Constructor & Destructor Documentation

object_database::ObjectDatabaseEntry::ObjectDatabaseEntry ( ObjectDatabaseRecognizer recognizerPtr,
const std::string  uniqueName,
const fs::path  path,
const fs::path  rvizMeshResourcePath,
const fs::path  normalVectorResourcePath 
)

Creates a new database entry.

Parameters:
recognizerPtrraw pointer to the type this entry belongs to - the passer guarantees for the lifetime of this pointer.
uniqueNamethe unique name this entry is identified by.
paththe path to the entries definition file or directory.

Definition at line 38 of file ObjectDatabaseEntry.cpp.

object_database::ObjectDatabaseEntry::ObjectDatabaseEntry ( ObjectDatabaseRecognizer recognizerPtr,
const std::string  uniqueName,
const fs::path  path,
const fs::path  rvizMeshResourcePath,
const fs::path  normalVectorResourcePath,
const fs::path  getDeviationResourcePath,
const fs::path  rotation_invariance_resource_path 
)

Definition at line 50 of file ObjectDatabaseEntry.cpp.

Definition at line 57 of file ObjectDatabaseEntry.h.


Member Function Documentation

Definition at line 186 of file ObjectDatabaseEntry.cpp.

Definition at line 191 of file ObjectDatabaseEntry.cpp.

Returns:
the path to the normal vector definition file.

Definition at line 88 of file ObjectDatabaseEntry.cpp.

std::vector< geometry_msgs::Point > object_database::ObjectDatabaseEntry::getNormalVectors ( )

Definition at line 93 of file ObjectDatabaseEntry.cpp.

Returns:
the path to the entries definition file or directory.

Definition at line 78 of file ObjectDatabaseEntry.cpp.

Returns:
the raw pointer to the object recognizer.

Definition at line 68 of file ObjectDatabaseEntry.cpp.

Returns:
whether the object is rotation invariant.

Definition at line 243 of file ObjectDatabaseEntry.cpp.

Definition at line 238 of file ObjectDatabaseEntry.cpp.

Returns:
the path to the entries definition file or directory.

Definition at line 83 of file ObjectDatabaseEntry.cpp.

Returns:
the unique name of the entry

Definition at line 73 of file ObjectDatabaseEntry.cpp.


Member Data Documentation

Path containing the definition of deviation

Definition at line 128 of file ObjectDatabaseEntry.h.

Definition at line 136 of file ObjectDatabaseEntry.h.

Path containing the definition of normal vector.

Definition at line 123 of file ObjectDatabaseEntry.h.

std::vector<geometry_msgs::Point> object_database::ObjectDatabaseEntry::mNormalVectors [private]

Definition at line 135 of file ObjectDatabaseEntry.h.

Path containing the definition path or directory.

Definition at line 113 of file ObjectDatabaseEntry.h.

Raw pointer to Object Database recognizer.

Definition at line 103 of file ObjectDatabaseEntry.h.

Path containing the definition path or directory.

Definition at line 118 of file ObjectDatabaseEntry.h.

String containing the unique name.

Definition at line 108 of file ObjectDatabaseEntry.h.

Path containing the definition of rotation invariance

Definition at line 133 of file ObjectDatabaseEntry.h.

Definition at line 137 of file ObjectDatabaseEntry.h.


The documentation for this class was generated from the following files:


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 Thu Jun 6 2019 21:11:02