ORLearningModule.h
Go to the documentation of this file.
00001 /*******************************************************************************
00002  *  ORLearningModule.h
00003  *
00004  *  (C) 2005, 2013 AG Aktives Sehen <agas@uni-koblenz.de>
00005  *                 Universitaet Koblenz-Landau
00006  *
00007  ******************************************************************************/
00008 
00009 #ifndef ORLearningModule_H
00010 #define ORLearningModule_H
00011 
00012 #include <string>
00013 #include <map>
00014 
00015 #include "ros/ros.h"
00016 #include <or_msgs/OrLearnCommand.h>
00017 #include <or_msgs/OrImage.h>
00018 #include <sensor_msgs/Image.h>
00019 
00020 #include <cv_bridge/cv_bridge.h>
00021 #include <sensor_msgs/image_encodings.h>
00022 #include <opencv2/imgproc/imgproc.hpp>
00023 #include <opencv2/highgui/highgui.hpp>
00024 
00025 #include "Architecture/StateMachine/StateMachine.h"
00026 
00027 class ObjectProperties;
00028 class ImagePropertiesCV;
00029 
00035 class ORLearningModule
00036 {
00037 
00038   public:
00039 
00040     enum CommandId {
00041       SetDifferenceThreshold,
00042       SetOpenRadius,
00043       SetIsolateLargestSegment,
00044       SetBorderSize,
00045       SetObjectType,
00046       GrabBackgroundImage,
00047       GrabForegroundImage,
00048       LoadBackgroundImage,
00049       LoadForegroundImage,
00050       DisplayImage,
00051       SaveImage,
00052       DeleteImage,
00053       LoadObject,
00054       SaveObject
00055     };
00056 
00057     enum ValueT {
00058       NoValue,
00059       FloatValue,
00060       StringValue,
00061       IntValue
00062     };
00063 
00065     enum ModuleState
00066     {
00067       IDLE,
00068       WAITING_FOR_BACKGROUND,
00069       WAITING_FOR_FOREGROUND
00070     };
00071 
00072     ORLearningModule(ros::NodeHandle *nh, std::string inputTopic);
00073 
00074     virtual ~ORLearningModule();
00075 
00076   private:
00077 
00078     void callbackOrLearnCommand( const or_msgs::OrLearnCommand::ConstPtr& msg );
00079     void callbackImage( const sensor_msgs::Image::ConstPtr& msg );
00080     void processImageMessage( const sensor_msgs::Image::ConstPtr& msg );
00081 
00082     void loadImage(std::string path);
00083 
00087     void saveObject ( std::string objectName );
00088 
00089     void loadObject ( std::string objectName );
00090 
00091     void displayImage ( int index );
00092 
00093     void deleteImage ( int index );
00094 
00095     void saveImage ( std::string name );
00096 
00097     void setBackground ( cv_bridge::CvImagePtr gray_image, cv_bridge::CvImagePtr color_image );
00098 
00099     void setForeground ( cv_bridge::CvImagePtr gray_image, cv_bridge::CvImagePtr color_image );
00100 
00101     void previewIsolatedImage();
00102 
00103     ImagePropertiesCV* makeImageProperties( std::string name="", bool crop=true );
00104 
00106     std::string m_PathForSaving;
00107     unsigned m_HistogramBinSize;
00108     unsigned m_HistogramMinY;
00109     unsigned m_HistogramMaxY;
00110 
00111     float m_HistogramClearRange;
00112 
00113     cv::Mat* m_BackgroundImageGray;
00114     cv::Mat* m_BackgroundImageColor;
00115     cv::Mat* m_ForegroundImageGray;
00116     cv::Mat* m_ForegroundImageColor;
00117 
00118     ObjectProperties* m_ObjectProperties;
00119 
00120     std::string m_ObjectType;
00121 
00122     float m_DifferenceThreshold;
00123     float m_OpenRadius;
00124     float m_BorderSize;
00125     bool  m_IsolateLargestSegment;
00126 
00127     StateMachine<ModuleState> m_ModuleMachine;
00128 
00129     std::string m_SimpleImagePath;
00130 
00131     bool m_ImageRequested;
00132 
00133     ros::Subscriber m_ORLearnCommandSubscriber;
00134     ros::Subscriber m_ORImageSubscriber;
00135     ros::Subscriber m_ImageSubscriber;
00136 
00137     ros::Publisher m_OLPrimaryImagePublisher;
00138     ros::Publisher m_OLDebugImagePublisher;
00139     ros::Publisher m_ORLearningStatusPublisher;
00140 };
00141 
00142 #endif


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