image_recorder_alg_node.cpp
Go to the documentation of this file.
00001 #include "image_recorder_alg_node.h"
00002 
00003 ImageRecorderAlgNode::ImageRecorderAlgNode(void) :
00004   algorithm_base::IriBaseAlgorithm<ImageRecorderAlgorithm>(),
00005   iit_database(0),
00006   list_pointer(0)
00007 {
00008   //init class attributes if necessary
00009   //this->loop_rate_ = 2;//in [Hz]
00010 
00011   // [init publishers]
00012   
00013   // [init subscribers]
00014   this->input_subscriber_ = this->public_node_handle_.subscribe("image", 100, &ImageRecorderAlgNode::input_callback, this);
00015   
00016   // [init services]
00017   
00018   // [init clients]
00019   
00020   // [init action servers]
00021   
00022   // [init action clients]
00023 }
00024 
00025 ImageRecorderAlgNode::~ImageRecorderAlgNode(void)
00026 {
00027   // [free dynamic memory]
00028 }
00029 
00030 void ImageRecorderAlgNode::mainNodeThread(void)
00031 {
00032   // [fill msg structures]
00033   
00034   // [fill srv structure and make request to the server]
00035   
00036   // [fill action structure and make request to the action server]
00037 
00038   // [publish messages]
00039 }
00040 
00041 /*  [subscriber callbacks] */
00042 void ImageRecorderAlgNode::input_callback(const sensor_msgs::ImageConstPtr& msg) 
00043 { 
00044   ROS_INFO("ImageRecorderAlgNode::input_callback: New Message Received"); 
00045 
00046   //use appropiate mutex to shared variables if necessary 
00047   //this->alg_.lock(); 
00048   //this->input_mutex_.enter(); 
00049   iit_database ++;
00050   
00051   std::string fileString = path + "/list.lst";
00052   ROS_INFO("path=%s",path.c_str());
00053   FILE * file_out;
00054   file_out = fopen (  fileString.c_str() , "r");
00055   fseek(file_out , list_pointer*(iit_database -1) , SEEK_SET );
00056   char file_name[64];
00057   if (fscanf(file_out, "%s\n" , file_name) != EOF) { 
00058     std::string string_file_name = file_name;
00059     fileString = path + string_file_name;
00060 
00062     IplImage *img = 0;
00063     std::string cv_encoding="passthrough";
00064     sensor_msgs::CvBridge bridge;
00065     img = bridge.imgMsgToCv(msg, cv_encoding);
00066     IplImage *frame = img;
00068 //    IplImage *frame = ImageRecorderAlgNode::getIplImage(msg); 
00069 //    ROS_INFO("%s",fileString.c_str()); 
00070 //    ROS_INFO("frame=%d", (int)frame);
00071     cvSaveImage(fileString.c_str(),frame);
00072   //  cvWaitKey(0);    
00073   //  cvReleaseImage(&frame);
00074   //std::cout << msg->data << std::endl; 
00075   }
00076 
00077   if (list_pointer == 0)
00078     list_pointer = strlen(file_name) + 1;
00079   fclose(file_out);
00080 
00081   //unlock previously blocked shared variables 
00082   //this->alg_.unlock(); 
00083   //this->input_mutex_.exit(); 
00084 }
00085 
00086 /*  [service callbacks] */
00087 
00088 /*  [action callbacks] */
00089 
00090 /*  [action requests] */
00091 
00092 void ImageRecorderAlgNode::node_config_update(Config &config, uint32_t level)
00093 {
00094   this->alg_.lock();
00095         path   = config.images_path;
00096   this->alg_.unlock();
00097 }
00098 
00099 void ImageRecorderAlgNode::addNodeDiagnostics()
00100 {
00101 }
00102 
00103 
00104 /* main function */
00105 int main(int argc,char *argv[])
00106 {
00107   return algorithm_base::main<ImageRecorderAlgNode>(argc, argv, "image_recorder_alg_node");
00108 }


iri_image_recorder
Author(s): Àngel Sanatamaria Navarro
autogenerated on Fri Dec 6 2013 19:55:05