#include <ObjectDetectorClass.h>
Classes | |
struct | tArguments |
Public Member Functions | |
ObjectDetectorClass () | |
void | runObjectDetectorDummyNode (int argc, char *argv[], const std::vector< std::string > &local_paths) |
void | runObjectDetectorNode (int argc, char *argv[]) |
virtual | ~ObjectDetectorClass () |
Protected Member Functions | |
void | createDebugDir (std::string &debug_dir) const |
void | initiateNode () |
void | loadLocalModel (ObjectDetectorProvider &provider) |
void | parseArgs (int argc, char *argv[]) |
void | spinNode () |
Protected Attributes | |
tArguments | m_arguments |
ros::NodeHandle * | m_node_handle |
std::string | m_node_name |
ObjectDetectorProvider * | m_provider |
Definition at line 41 of file ObjectDetectorClass.h.
Definition at line 48 of file ObjectDetectorClass.cpp.
ObjectDetectorClass::~ObjectDetectorClass | ( | ) | [virtual] |
Definition at line 55 of file ObjectDetectorClass.cpp.
void ObjectDetectorClass::createDebugDir | ( | std::string & | debug_dir | ) | const [protected] |
Creates a debug directory and returns its location
debug_dir | location of created dir |
Definition at line 204 of file ObjectDetectorClass.cpp.
void ObjectDetectorClass::initiateNode | ( | ) | [protected] |
Checks the data and initiates the node
Definition at line 159 of file ObjectDetectorClass.cpp.
void ObjectDetectorClass::loadLocalModel | ( | ObjectDetectorProvider & | provider | ) | [protected] |
Loads a model of a poster whose location is fixed
void ObjectDetectorClass::parseArgs | ( | int | argc, |
char * | argv[] | ||
) | [protected] |
Parses the arguments given
Definition at line 99 of file ObjectDetectorClass.cpp.
void ObjectDetectorClass::runObjectDetectorDummyNode | ( | int | argc, |
char * | argv[], | ||
const std::vector< std::string > & | local_paths | ||
) |
Initiates the ObjectDetectorDummy node
argc | |
argv |
Definition at line 76 of file ObjectDetectorClass.cpp.
void ObjectDetectorClass::runObjectDetectorNode | ( | int | argc, |
char * | argv[] | ||
) |
Initiates the ObjectDetector node
argc | |
argv |
Definition at line 63 of file ObjectDetectorClass.cpp.
void ObjectDetectorClass::spinNode | ( | ) | [protected] |
Runs ros::spin
Definition at line 196 of file ObjectDetectorClass.cpp.
tArguments ObjectDetectorClass::m_arguments [protected] |
Definition at line 102 of file ObjectDetectorClass.h.
ros::NodeHandle* ObjectDetectorClass::m_node_handle [protected] |
Definition at line 104 of file ObjectDetectorClass.h.
std::string ObjectDetectorClass::m_node_name [protected] |
Definition at line 103 of file ObjectDetectorClass.h.
ObjectDetectorProvider* ObjectDetectorClass::m_provider [protected] |
Definition at line 105 of file ObjectDetectorClass.h.