00001 #include "compressed_image_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_image_transport {
00008
00009 void CompressedSubscriber::internalCallback(const sensor_msgs::CompressedImageConstPtr& message,
00010 const Callback& user_cb)
00011 {
00013
00014 const CvMat compressed = cvMat(1, message->data.size(), CV_8UC1,
00015 const_cast<unsigned char*>(&message->data[0]));
00016 cv::WImageBuffer_b decompressed( cvDecodeImage(&compressed, CV_LOAD_IMAGE_ANYCOLOR) );
00017
00018
00019 boost::shared_ptr<sensor_msgs::Image> image_ptr(new sensor_msgs::Image);
00020 if ( !sensor_msgs::CvBridge::fromIpltoRosImage(decompressed.Ipl(), *image_ptr) ) {
00021 ROS_ERROR("Unable to create image message");
00022 return;
00023 }
00024 image_ptr->header = message->header;
00025 image_ptr->__connection_header = message->__connection_header;
00027 if (decompressed.Channels() == 1) {
00028 image_ptr->encoding = sensor_msgs::image_encodings::MONO8;
00029 }
00030 else if (decompressed.Channels() == 3) {
00031 image_ptr->encoding = sensor_msgs::image_encodings::BGR8;
00032 }
00033 else {
00034 ROS_ERROR("Unsupported number of channels: %i", decompressed.Channels());
00035 return;
00036 }
00037
00038 user_cb(image_ptr);
00039 }
00040
00041 }