00001 #include "compressed_imagem_transport/compressed_subscriber.h"
00002 #include <sensor_msgs/image_encodings.h>
00003 #include <cv_bridge/CvBridge.h>
00004 #include <opencv/cvwimage.h>
00005 #include <opencv/highgui.h>
00006
00007 namespace compressed_imagem_transport {
00008
00009 void CompressedSubscriber::internalCallback(const sensor_msgs::CompressedImageConstPtr& message,
00010 const message_transport::SimpleSubscriberPlugin<sensor_msgs::Image,sensor_msgs::CompressedImage>::Callback& user_cb)
00011 {
00012
00013 const CvMat compressed = cvMat(1, message->data.size(), CV_8UC1,
00014 const_cast<unsigned char*>(&message->data[0]));
00015 cv::WImageBuffer_b decompressed( cvDecodeImage(&compressed, CV_LOAD_IMAGE_ANYCOLOR) );
00016
00017
00018 boost::shared_ptr<sensor_msgs::Image> image_ptr(new sensor_msgs::Image);
00019 if ( !sensor_msgs::CvBridge::fromIpltoRosImage(decompressed.Ipl(), *image_ptr) ) {
00020 ROS_ERROR("Unable to create image message");
00021 return;
00022 }
00023 image_ptr->header = message->header;
00024
00025 if (decompressed.Channels() == 1) {
00026 image_ptr->encoding = sensor_msgs::image_encodings::MONO8;
00027 }
00028 else if (decompressed.Channels() == 3) {
00029 image_ptr->encoding = sensor_msgs::image_encodings::BGR8;
00030 }
00031 else {
00032 ROS_ERROR("Unsupported number of channels: %i", decompressed.Channels());
00033 return;
00034 }
00035
00036 user_cb(image_ptr);
00037 }
00038
00039 }