00001 #include "compressed_imagem_transport/compressed_publisher.h"
00002 #include <sensor_msgs/image_encodings.h>
00003 #include <cv_bridge/CvBridge.h>
00004 #include <opencv/highgui.h>
00005
00006 namespace compressed_imagem_transport {
00007
00008 void CompressedPublisher::publish(const sensor_msgs::Image& message,
00009 const message_transport::SimplePublisherPlugin<sensor_msgs::Image,sensor_msgs::CompressedImage>::PublishFn& publish_fn) const
00010 {
00011
00012 sensor_msgs::CvBridge bridge;
00013
00014
00015 if (bridge.encoding_as_fmt(message.encoding) == "GRAY") {
00016 if (!bridge.fromImage(message, sensor_msgs::image_encodings::MONO8)) {
00017 ROS_ERROR("Could not convert image from %s to mono8", message.encoding.c_str());
00018 return;
00019 }
00020 }
00021 else if (!bridge.fromImage(message, sensor_msgs::image_encodings::BGR8)) {
00022 ROS_ERROR("Could not convert image from %s to bgr8", message.encoding.c_str());
00023 return;
00024 }
00025
00026
00027 int params[3] = {0};
00028 std::string format, format_param;
00029 if (!getParamNode().searchParam("compressed_image_transport_format", format_param) ||
00030 !getParamNode().getParamCached(format_param, format))
00031 format = "jpeg";
00032 if (format == "jpeg") {
00033 params[0] = CV_IMWRITE_JPEG_QUALITY;
00034 std::string quality_param;
00035 if (!getParamNode().searchParam("compressed_image_transport_jpeg_quality", quality_param) ||
00036 !getParamNode().getParamCached(quality_param, params[1]))
00037 params[1] = 80;
00038 }
00039 else if (format == "png") {
00040 params[0] = CV_IMWRITE_PNG_COMPRESSION;
00041 std::string level_param;
00042 if (!getParamNode().searchParam("compressed_image_transport_png_level", level_param) ||
00043 !getParamNode().getParamCached(level_param, params[1]))
00044 params[1] = 9;
00045 }
00046 else {
00047 ROS_ERROR("Unknown compression type '%s', valid options are 'jpeg' and 'png'",
00048 format.c_str());
00049 return;
00050 }
00051 std::string extension = '.' + format;
00052
00053
00054 const IplImage* image = bridge.toIpl();
00055 CvMat* buf = cvEncodeImage(extension.c_str(), image, params);
00056
00057
00058 sensor_msgs::CompressedImage compressed;
00059 compressed.header = message.header;
00060 compressed.format = format;
00061 compressed.data.resize(buf->width);
00062 memcpy(&compressed.data[0], buf->data.ptr, buf->width);
00063 cvReleaseMat(&buf);
00064
00065 publish_fn(compressed);
00066 }
00067
00068 }