raw_image_subscriber.cpp
Go to the documentation of this file.
00001 /*
00002  * raw_image_subscriber.cpp
00003  *
00004  *  Created on: Aug 31, 2010
00005  *      Author: petrito1@cmp.felk.cvut.cz
00006  */
00007 
00008 #include <cv_bridge/CvBridge.h>
00009 #include <image_transport/image_transport.h>
00010 #include <opencv2/core/core.hpp>
00011 #include <opencv2/highgui/highgui.hpp>
00012 #include <ros/ros.h>
00013 
00014 namespace {
00015 std::string nodeName = "raw_image_subscriber";
00016 std::string imageTopic = "raw";
00017 }
00018 
00019 //void imageCallback(const sensor_msgs::ImagePtr &msg) {
00020 void imageCallback(const sensor_msgs::ImageConstPtr &msg) {
00021 
00022   ROS_DEBUG("Message received: size: %dx%d, step: %d, encoding: %s", msg->width, msg->height, msg->step,
00023       msg->encoding.data());
00024 
00025   sensor_msgs::CvBridge bridge;
00026 //  IplImage* iplImage = bridge.imgMsgToCv(msg, "passthrough");
00027     IplImage* iplImage = bridge.imgMsgToCv(msg, "mono8");
00028 
00029   cv::Mat inImage(iplImage);
00030   ROS_DEBUG("In image: size: %dx%d, step: %d, type: %d", inImage.cols, inImage.rows, inImage.step, inImage.type());
00031 
00032   cv::Mat outImage;
00033   // The output RGB components of a pixel are interpolated from 1, 2 or 4 neighbors of the pixel having the same color.
00034   cv::cvtColor(inImage, outImage, CV_BayerBG2BGR);
00035   ROS_DEBUG("Out image: size: %dx%d, step: %d, type: %d", outImage.cols, outImage.rows, outImage.step, outImage.type());
00036   cv::Mat small;
00037   cv::resize(outImage, small, cv::Size(), 0.125, 0.125);
00038   cv::imshow(nodeName, small);
00039 }
00040 
00041 int main(int argc, char **argv) {
00042 
00043   ros::init(argc, argv, nodeName);
00044   ros::NodeHandle nh;
00045   image_transport::ImageTransport it(nh);
00046   cv::namedWindow(nodeName);
00047   cvStartWindowThread();
00048   image_transport::Subscriber sub = it.subscribe(imageTopic, 1, imageCallback);
00049   ros::spin();
00050   cvDestroyWindow(nodeName.data());
00051 }
00052 
 All Classes Namespaces Files Functions Variables Typedefs Defines


omnicamera
Author(s): Tomas Petricek / petrito1@cmp.felk.cvut.cz
autogenerated on Tue Dec 10 2013 14:26:53