Public Types | Public Member Functions | Private Member Functions | Private Attributes
ORControlModule Class Reference

Controls the Object Recognition Process. More...

#include <ORControlModule.h>

List of all members.

Public Types

enum  CommandId {
  LoadObject, UnloadObject, LoadSingleImage, GrabSingleImage,
  StartRecognitionLoop, StopRecognitionLoop
}
enum  ValueT { NoValue, FloatValue, StringValue, IntValue }

Public Member Functions

 ORControlModule (ros::NodeHandle *nh, ORMatchingModule *objRecMatchingModule)
 The constructor.
virtual ~ORControlModule ()
 The destructor.

Private Member Functions

void callbackOrCommand (const or_msgs::OrCommand::ConstPtr &msg)
void callbackOrMatchResult (const or_msgs::OrMatchResult::ConstPtr &msg)

Private Attributes

std::vector
< or_msgs::BoundingBox2D > 
m_BoundingBoxes
bool m_Continuous
ros::Publisher m_DebugImagePublisher
ros::Publisher m_DebugImagePublisherColor
ros::Publisher m_DebugImagePublisherGray
ros::Publisher m_ExtractKeyPointsPublisher
int m_ImagesInPipeline
int m_MaxImagesInPipeline
ros::Subscriber m_ORCommandSubscriber
ORMatchingModulem_ORMatchingModule
ros::Subscriber m_ORMatchResultSubscriber
int m_SourceId

Detailed Description

Controls the Object Recognition Process.

Author:
David Gossow (RX), Viktor Seib (R20)

Definition at line 23 of file ORControlModule.h.


Member Enumeration Documentation

Enumerator:
LoadObject 
UnloadObject 
LoadSingleImage 
GrabSingleImage 
StartRecognitionLoop 
StopRecognitionLoop 

Definition at line 27 of file ORControlModule.h.

Enumerator:
NoValue 
FloatValue 
StringValue 
IntValue 

Definition at line 36 of file ORControlModule.h.


Constructor & Destructor Documentation

ORControlModule::ORControlModule ( ros::NodeHandle nh,
ORMatchingModule objRecMatchingModule 
)

The constructor.

virtual ORControlModule::~ORControlModule ( ) [virtual]

The destructor.


Member Function Documentation

void ORControlModule::callbackOrCommand ( const or_msgs::OrCommand::ConstPtr &  msg) [private]
void ORControlModule::callbackOrMatchResult ( const or_msgs::OrMatchResult::ConstPtr &  msg) [private]

Member Data Documentation

std::vector<or_msgs::BoundingBox2D> ORControlModule::m_BoundingBoxes [private]

Definition at line 62 of file ORControlModule.h.

Definition at line 57 of file ORControlModule.h.

Definition at line 68 of file ORControlModule.h.

Definition at line 71 of file ORControlModule.h.

Definition at line 70 of file ORControlModule.h.

Definition at line 67 of file ORControlModule.h.

Definition at line 54 of file ORControlModule.h.

Definition at line 55 of file ORControlModule.h.

Definition at line 64 of file ORControlModule.h.

Definition at line 59 of file ORControlModule.h.

Definition at line 65 of file ORControlModule.h.

Definition at line 61 of file ORControlModule.h.


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


or_nodes
Author(s): raphael
autogenerated on Mon Oct 6 2014 02:53:36