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

This module learns objects with camera images by color and SURF-features. More...

#include <ORLearningModule.h>

List of all members.

Public Types

enum  CommandId {
  SetDifferenceThreshold, SetOpenRadius, SetIsolateLargestSegment, SetBorderSize,
  SetObjectType, GrabBackgroundImage, GrabForegroundImage, LoadBackgroundImage,
  LoadForegroundImage, DisplayImage, SaveImage, DeleteImage,
  LoadObject, SaveObject
}
enum  ModuleState { IDLE, WAITING_FOR_BACKGROUND, WAITING_FOR_FOREGROUND }
 Define an enum type for the states of each machine here. More...
enum  ValueT { NoValue, FloatValue, StringValue, IntValue }

Public Member Functions

 ORLearningModule (ros::NodeHandle *nh, std::string inputTopic)
virtual ~ORLearningModule ()

Private Member Functions

void callbackImage (const sensor_msgs::Image::ConstPtr &msg)
void callbackOrLearnCommand (const or_msgs::OrLearnCommand::ConstPtr &msg)
void deleteImage (int index)
void displayImage (int index)
void loadImage (std::string path)
void loadObject (std::string objectName)
ImagePropertiesCVmakeImageProperties (std::string name="", bool crop=true)
void previewIsolatedImage ()
void processImageMessage (const sensor_msgs::Image::ConstPtr &msg)
void saveImage (std::string name)
void saveObject (std::string objectName)
 This method stores an objectProperties object to disk.
void setBackground (cv_bridge::CvImagePtr gray_image, cv_bridge::CvImagePtr color_image)
void setForeground (cv_bridge::CvImagePtr gray_image, cv_bridge::CvImagePtr color_image)

Private Attributes

cv::Mat * m_BackgroundImageColor
cv::Mat * m_BackgroundImageGray
float m_BorderSize
float m_DifferenceThreshold
cv::Mat * m_ForegroundImageColor
cv::Mat * m_ForegroundImageGray
unsigned m_HistogramBinSize
float m_HistogramClearRange
unsigned m_HistogramMaxY
unsigned m_HistogramMinY
bool m_ImageRequested
ros::Subscriber m_ImageSubscriber
bool m_IsolateLargestSegment
StateMachine< ModuleStatem_ModuleMachine
ObjectPropertiesm_ObjectProperties
std::string m_ObjectType
ros::Publisher m_OLDebugImagePublisher
ros::Publisher m_OLPrimaryImagePublisher
float m_OpenRadius
ros::Subscriber m_ORImageSubscriber
ros::Subscriber m_ORLearnCommandSubscriber
ros::Publisher m_ORLearningStatusPublisher
std::string m_PathForSaving
 Configuration parameters.
std::string m_SimpleImagePath

Detailed Description

This module learns objects with camera images by color and SURF-features.

Author:
Patric Lambrecht, Jan Bornemeier (RX), David Gossow (RX), Viktor Seib (R20)

Definition at line 35 of file ORLearningModule.h.


Member Enumeration Documentation

Enumerator:
SetDifferenceThreshold 
SetOpenRadius 
SetIsolateLargestSegment 
SetBorderSize 
SetObjectType 
GrabBackgroundImage 
GrabForegroundImage 
LoadBackgroundImage 
LoadForegroundImage 
DisplayImage 
SaveImage 
DeleteImage 
LoadObject 
SaveObject 

Definition at line 40 of file ORLearningModule.h.

Define an enum type for the states of each machine here.

Enumerator:
IDLE 
WAITING_FOR_BACKGROUND 
WAITING_FOR_FOREGROUND 

Definition at line 65 of file ORLearningModule.h.

Enumerator:
NoValue 
FloatValue 
StringValue 
IntValue 

Definition at line 57 of file ORLearningModule.h.


Constructor & Destructor Documentation

ORLearningModule::ORLearningModule ( ros::NodeHandle *  nh,
std::string  inputTopic 
)
virtual ORLearningModule::~ORLearningModule ( ) [virtual]

Member Function Documentation

void ORLearningModule::callbackImage ( const sensor_msgs::Image::ConstPtr &  msg) [private]
void ORLearningModule::callbackOrLearnCommand ( const or_msgs::OrLearnCommand::ConstPtr &  msg) [private]
void ORLearningModule::deleteImage ( int  index) [private]
void ORLearningModule::displayImage ( int  index) [private]
void ORLearningModule::loadImage ( std::string  path) [private]
void ORLearningModule::loadObject ( std::string  objectName) [private]
ImagePropertiesCV* ORLearningModule::makeImageProperties ( std::string  name = "",
bool  crop = true 
) [private]
void ORLearningModule::processImageMessage ( const sensor_msgs::Image::ConstPtr &  msg) [private]
void ORLearningModule::saveImage ( std::string  name) [private]
void ORLearningModule::saveObject ( std::string  objectName) [private]

This method stores an objectProperties object to disk.

void ORLearningModule::setBackground ( cv_bridge::CvImagePtr  gray_image,
cv_bridge::CvImagePtr  color_image 
) [private]
void ORLearningModule::setForeground ( cv_bridge::CvImagePtr  gray_image,
cv_bridge::CvImagePtr  color_image 
) [private]

Member Data Documentation

Definition at line 114 of file ORLearningModule.h.

Definition at line 113 of file ORLearningModule.h.

Definition at line 124 of file ORLearningModule.h.

Definition at line 122 of file ORLearningModule.h.

Definition at line 116 of file ORLearningModule.h.

Definition at line 115 of file ORLearningModule.h.

Definition at line 107 of file ORLearningModule.h.

Definition at line 111 of file ORLearningModule.h.

Definition at line 109 of file ORLearningModule.h.

Definition at line 108 of file ORLearningModule.h.

Definition at line 131 of file ORLearningModule.h.

ros::Subscriber ORLearningModule::m_ImageSubscriber [private]

Definition at line 135 of file ORLearningModule.h.

Definition at line 125 of file ORLearningModule.h.

Definition at line 127 of file ORLearningModule.h.

Definition at line 118 of file ORLearningModule.h.

std::string ORLearningModule::m_ObjectType [private]

Definition at line 120 of file ORLearningModule.h.

Definition at line 138 of file ORLearningModule.h.

Definition at line 137 of file ORLearningModule.h.

Definition at line 123 of file ORLearningModule.h.

ros::Subscriber ORLearningModule::m_ORImageSubscriber [private]

Definition at line 134 of file ORLearningModule.h.

Definition at line 133 of file ORLearningModule.h.

Definition at line 139 of file ORLearningModule.h.

std::string ORLearningModule::m_PathForSaving [private]

Configuration parameters.

Definition at line 106 of file ORLearningModule.h.

std::string ORLearningModule::m_SimpleImagePath [private]

Definition at line 129 of file ORLearningModule.h.


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


or_nodes
Author(s): Viktor Seib
autogenerated on Tue Jan 7 2014 11:24:09