This module learns objects with camera images by color and SURF-features. More...
#include <ORLearningModule.h>
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) |
ImagePropertiesCV * | makeImageProperties (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< ModuleState > | m_ModuleMachine |
ObjectProperties * | m_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 |
This module learns objects with camera images by color and SURF-features.
Definition at line 35 of file ORLearningModule.h.
Definition at line 40 of file ORLearningModule.h.
Define an enum type for the states of each machine here.
Definition at line 65 of file ORLearningModule.h.
Definition at line 57 of file ORLearningModule.h.
ORLearningModule::ORLearningModule | ( | ros::NodeHandle * | nh, |
std::string | inputTopic | ||
) |
virtual ORLearningModule::~ORLearningModule | ( | ) | [virtual] |
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::previewIsolatedImage | ( | ) | [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] |
cv::Mat* ORLearningModule::m_BackgroundImageColor [private] |
Definition at line 114 of file ORLearningModule.h.
cv::Mat* ORLearningModule::m_BackgroundImageGray [private] |
Definition at line 113 of file ORLearningModule.h.
float ORLearningModule::m_BorderSize [private] |
Definition at line 124 of file ORLearningModule.h.
float ORLearningModule::m_DifferenceThreshold [private] |
Definition at line 122 of file ORLearningModule.h.
cv::Mat* ORLearningModule::m_ForegroundImageColor [private] |
Definition at line 116 of file ORLearningModule.h.
cv::Mat* ORLearningModule::m_ForegroundImageGray [private] |
Definition at line 115 of file ORLearningModule.h.
unsigned ORLearningModule::m_HistogramBinSize [private] |
Definition at line 107 of file ORLearningModule.h.
float ORLearningModule::m_HistogramClearRange [private] |
Definition at line 111 of file ORLearningModule.h.
unsigned ORLearningModule::m_HistogramMaxY [private] |
Definition at line 109 of file ORLearningModule.h.
unsigned ORLearningModule::m_HistogramMinY [private] |
Definition at line 108 of file ORLearningModule.h.
bool ORLearningModule::m_ImageRequested [private] |
Definition at line 131 of file ORLearningModule.h.
ros::Subscriber ORLearningModule::m_ImageSubscriber [private] |
Definition at line 135 of file ORLearningModule.h.
bool ORLearningModule::m_IsolateLargestSegment [private] |
Definition at line 125 of file ORLearningModule.h.
StateMachine<ModuleState> ORLearningModule::m_ModuleMachine [private] |
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.
ros::Publisher ORLearningModule::m_OLDebugImagePublisher [private] |
Definition at line 138 of file ORLearningModule.h.
ros::Publisher ORLearningModule::m_OLPrimaryImagePublisher [private] |
Definition at line 137 of file ORLearningModule.h.
float ORLearningModule::m_OpenRadius [private] |
Definition at line 123 of file ORLearningModule.h.
ros::Subscriber ORLearningModule::m_ORImageSubscriber [private] |
Definition at line 134 of file ORLearningModule.h.
ros::Subscriber ORLearningModule::m_ORLearnCommandSubscriber [private] |
Definition at line 133 of file ORLearningModule.h.
ros::Publisher ORLearningModule::m_ORLearningStatusPublisher [private] |
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.