Controls the Object Recognition Process. More...
#include <ORControlModule.h>
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_ExtractKeyPointsPublisher | 
| int | m_ImagesInPipeline | 
| int | m_MaxImagesInPipeline | 
| ros::Subscriber | m_ORCommandSubscriber | 
| ORMatchingModule * | m_ORMatchingModule | 
| ros::Subscriber | m_ORMatchResultSubscriber | 
| int | m_SourceId | 
Controls the Object Recognition Process.
Definition at line 23 of file ORControlModule.h.
| LoadObject | |
| UnloadObject | |
| LoadSingleImage | |
| GrabSingleImage | |
| StartRecognitionLoop | |
| StopRecognitionLoop | 
Definition at line 27 of file ORControlModule.h.
Definition at line 36 of file ORControlModule.h.
| ORControlModule::ORControlModule | ( | ros::NodeHandle * | nh, | 
| ORMatchingModule * | objRecMatchingModule | ||
| ) | 
The constructor.
| virtual ORControlModule::~ORControlModule | ( | ) |  [virtual] | 
        
The destructor.
| void ORControlModule::callbackOrCommand | ( | const or_msgs::OrCommand::ConstPtr & | msg | ) |  [private] | 
        
| void ORControlModule::callbackOrMatchResult | ( | const or_msgs::OrMatchResult::ConstPtr & | msg | ) |  [private] | 
        
std::vector<or_msgs::BoundingBox2D> ORControlModule::m_BoundingBoxes [private] | 
        
Definition at line 62 of file ORControlModule.h.
bool ORControlModule::m_Continuous [private] | 
        
Definition at line 57 of file ORControlModule.h.
ros::Publisher ORControlModule::m_DebugImagePublisher [private] | 
        
Definition at line 68 of file ORControlModule.h.
ros::Publisher ORControlModule::m_ExtractKeyPointsPublisher [private] | 
        
Definition at line 67 of file ORControlModule.h.
int ORControlModule::m_ImagesInPipeline [private] | 
        
Definition at line 54 of file ORControlModule.h.
int ORControlModule::m_MaxImagesInPipeline [private] | 
        
Definition at line 55 of file ORControlModule.h.
ros::Subscriber ORControlModule::m_ORCommandSubscriber [private] | 
        
Definition at line 64 of file ORControlModule.h.
Definition at line 59 of file ORControlModule.h.
ros::Subscriber ORControlModule::m_ORMatchResultSubscriber [private] | 
        
Definition at line 65 of file ORControlModule.h.
int ORControlModule::m_SourceId [private] | 
        
Definition at line 61 of file ORControlModule.h.