ORControlModule.cpp
Go to the documentation of this file.
00001 /*******************************************************************************
00002  *  ORControlModule.cpp
00003  *
00004  *  (C) 2006 AG Aktives Sehen <agas@uni-koblenz.de>
00005  *           Universitaet Koblenz-Landau
00006  *
00007  *******************************************************************************/
00008 
00009 #include <sstream>
00010 
00011 #include <cv_bridge/cv_bridge.h>
00012 #include <sensor_msgs/image_encodings.h>
00013 //#include <sensor_msgs/Image.h>
00014 #include <opencv2/highgui/highgui.hpp>
00015 
00016 #include <or_msgs/BoundingBox2D.h>
00017 #include <or_msgs/ExtractKeyPoints.h>
00018 #include <or_msgs/OrImage.h>
00019 
00020 #include "Architecture/Config/Config.h"
00021 
00022 #include "ORControlModule.h"
00023 #include "ORMatchingModule.h"
00024 
00025 #define THIS ORControlModule
00026 
00027 THIS::THIS(ros::NodeHandle *nh, ORMatchingModule* objRecMatchingModule)
00028 {
00029     m_ORMatchingModule = objRecMatchingModule;
00030 
00031     m_ImagesInPipeline = 0;
00032     m_MaxImagesInPipeline = Config::getInt( "ObjectRecognition.iMaxImagesInPipeline" );
00033 
00034     m_Continuous = false;
00035 
00036     // subscribe to topics
00037     m_ORCommandSubscriber = nh->subscribe<or_msgs::OrCommand>("/or/commands", 10, &ORControlModule::callbackOrCommand, this);
00038     m_ORMatchResultSubscriber = nh->subscribe<or_msgs::OrMatchResult>("or/match_result", 10, &ORControlModule::callbackOrMatchResult, this);
00039 
00040     // advertise topics
00041     m_ExtractKeyPointsPublisher = nh->advertise<or_msgs::ExtractKeyPoints>("/or/extract", 10);
00042     m_DebugImagePublisher = nh->advertise<or_msgs::OrImage>("or/debug_image", 10);
00043 }
00044 
00045 
00046 THIS::~THIS()
00047 {}
00048 
00049 
00050 void THIS::callbackOrCommand( const or_msgs::OrCommand::ConstPtr& or_command_msg )
00051 {
00052     ROS_DEBUG_STREAM("or_command message received");
00053 
00054     std::vector<or_msgs::BoundingBox2D> m_BoundingBoxes = or_command_msg->bounding_boxes;
00055 
00056     switch (or_command_msg->command)
00057     {
00058     case ORControlModule::GrabSingleImage:
00059     {
00060         m_SourceId = or_command_msg->int_value; // TODO  m_SourceId = ImageSources::SourceId(message->getInt());
00061         // send message for keypoint extraction
00062         or_msgs::ExtractKeyPoints extract_msg;
00063         extract_msg.img_source = m_SourceId;
00064         extract_msg.bounding_boxes = m_BoundingBoxes;
00065         m_ExtractKeyPointsPublisher.publish(extract_msg);
00066 
00067         m_ImagesInPipeline++;
00068         m_Continuous = false;
00069         break;
00070     }
00071 
00072     case ORControlModule::LoadSingleImage:
00073     {
00074         std::string fileName = or_command_msg->string_value;
00075         ROS_INFO_STREAM("Loading image file: " << fileName);
00076 
00077         // send message for keypoint extraction
00078         or_msgs::ExtractKeyPoints extract_msg;
00079         extract_msg.img_source = 0; // TODO ImageSources::SourceId::None
00080         extract_msg.bounding_boxes = m_BoundingBoxes;
00081         m_ExtractKeyPointsPublisher.publish(extract_msg);
00082 
00083         //read and publish image
00084         cv_bridge::CvImage gray_image, color_image;
00085         gray_image.image = cv::imread(fileName.c_str(), CV_LOAD_IMAGE_GRAYSCALE);
00086         gray_image.encoding = sensor_msgs::image_encodings::TYPE_8UC1;
00087         color_image.image = cv::imread(fileName.c_str(), CV_LOAD_IMAGE_COLOR);
00088         color_image.encoding = sensor_msgs::image_encodings::TYPE_8UC3;
00089 
00090         or_msgs::OrImage or_image_msg;
00091         or_image_msg.image_gray = *(gray_image.toImageMsg());
00092         or_image_msg.image_color = *(color_image.toImageMsg());
00093         or_image_msg.filename = fileName;
00094         m_DebugImagePublisher.publish(or_image_msg);
00095 
00096         m_ImagesInPipeline++;
00097         m_Continuous = false;
00098 
00099         // pass loaded image directly to the matching module
00100         m_ORMatchingModule->processImageMessage(color_image.toImageMsg());
00101 
00102         break;
00103     }
00104 
00105     case ORControlModule::StartRecognitionLoop:
00106     {
00107         m_SourceId = or_command_msg->int_value; // TODO ImageSources::SourceId(message->getInt());
00108         for ( int i=0; i<m_MaxImagesInPipeline; i++ )
00109         {
00110             // send message for keypoint extraction
00111             or_msgs::ExtractKeyPoints extract_msg;
00112             extract_msg.img_source = m_SourceId;
00113             extract_msg.bounding_boxes = m_BoundingBoxes;
00114             m_ExtractKeyPointsPublisher.publish(extract_msg);
00115             m_ImagesInPipeline++;
00116         }
00117         m_Continuous = true;
00118         break;
00119     }
00120 
00121     case ORControlModule::StopRecognitionLoop:
00122     {
00123         m_Continuous = false;
00124         break;
00125     }
00126 
00127     default:
00128         break;
00129     }
00130 }
00131 
00132 void THIS::callbackOrMatchResult( const or_msgs::OrMatchResult::ConstPtr& or_match_result_msg)
00133 {
00134     // TODO only for debug
00135     if(or_match_result_msg->match_results.size() == 0)
00136         ROS_ERROR_STREAM("no objects recognized");
00137     else
00138     {
00139            ROS_ERROR_STREAM("recognized objects: ");
00140     for(unsigned i = 0; i < or_match_result_msg->match_results.size(); i++)
00141         ROS_ERROR_STREAM(or_match_result_msg->match_results.at(i).object_name);
00142     }
00143 
00144 
00145     if ( m_Continuous )
00146     {
00147         // send message for keypoint extraction
00148         or_msgs::ExtractKeyPoints extract_msg;
00149         extract_msg.img_source = m_SourceId;
00150         extract_msg.bounding_boxes = m_BoundingBoxes;
00151         m_ExtractKeyPointsPublisher.publish(extract_msg);
00152         m_ImagesInPipeline++;
00153     }
00154     m_ImagesInPipeline--;
00155 }
00156 
00157 
00158 #undef THIS


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