Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00040 #include <ros/ros.h>
00041 #include <sensor_msgs/CompressedImage.h>
00042 #include <sensor_msgs/image_encodings.h>
00043 #include <nodelet/nodelet.h>
00044 #include <image_transport/image_transport.h>
00045 #include <cv_bridge/cv_bridge.h>
00046 #include <sensor_msgs/image_encodings.h>
00047
00048 #include <opencv2/highgui/highgui.hpp>
00049 #include <opencv2/imgproc/imgproc.hpp>
00050
00051 #include <dynamic_reconfigure/server.h>
00052
00053 namespace opencv_apps
00054 {
00055 namespace simple_compressed_example
00056 {
00057 static const std::string OPENCV_WINDOW = "Image window";
00058
00059 class ImageConverter
00060 {
00061 ros::NodeHandle nh_;
00062 ros::Subscriber image_sub_;
00063 ros::Publisher image_pub_;
00064 int queue_size_;
00065 bool debug_view_;
00066
00067 public:
00068 ImageConverter()
00069 {
00070
00071 image_sub_ = nh_.subscribe("image/compressed", queue_size_, &ImageConverter::imageCb, this);
00072 image_pub_ = nh_.advertise<sensor_msgs::CompressedImage>("/image_converter/output_video/compressed", 1);
00073
00074 ros::NodeHandle pnh("~");
00075 pnh.param("queue_size", queue_size_, 3);
00076 pnh.param("debug_view", debug_view_, false);
00077 if (debug_view_)
00078 {
00079 cv::namedWindow(OPENCV_WINDOW);
00080 }
00081 }
00082
00083 ~ImageConverter()
00084 {
00085 if (debug_view_)
00086 {
00087 cv::destroyWindow(OPENCV_WINDOW);
00088 }
00089 }
00090
00091 void imageCb(const sensor_msgs::CompressedImageConstPtr& msg)
00092 {
00093 cv_bridge::CvImagePtr cv_ptr;
00094 try
00095 {
00096
00097
00098
00099
00100
00101 #ifndef CV_BRIDGE_COMPRESSED_IMAGE_IS_NOT_SUPPORTED
00102 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
00103 #else
00104
00105
00106
00107 cv::Mat jpegData(1, msg->data.size(), CV_8UC1);
00108 jpegData.data = const_cast<uchar*>(&msg->data[0]);
00109 cv::InputArray data(jpegData);
00110 cv::Mat image = cv::imdecode(data, cv::IMREAD_COLOR);
00111
00112
00113
00114 sensor_msgs::Image ros_image;
00115 ros_image.header = msg->header;
00116 ros_image.height = image.rows;
00117 ros_image.width = image.cols;
00118 ros_image.encoding = sensor_msgs::image_encodings::BGR8;
00119 ros_image.is_bigendian = false;
00120 ros_image.step = image.cols * image.elemSize();
00121 size_t size = ros_image.step * image.rows;
00122 ros_image.data.resize(size);
00123
00124 if (image.isContinuous())
00125 {
00126 memcpy((char*)(&ros_image.data[0]), image.data, size);
00127 }
00128 else
00129 {
00130
00131 uchar* ros_data_ptr = (uchar*)(&ros_image.data[0]);
00132 uchar* cv_data_ptr = image.data;
00133 for (int i = 0; i < image.rows; ++i)
00134 {
00135 memcpy(ros_data_ptr, cv_data_ptr, ros_image.step);
00136 ros_data_ptr += ros_image.step;
00137 cv_data_ptr += image.step;
00138 }
00139 }
00140 cv_ptr = cv_bridge::toCvCopy(ros_image, sensor_msgs::image_encodings::BGR8);
00141 #endif
00142 }
00143 catch (cv_bridge::Exception& e)
00144 {
00145 ROS_ERROR("cv_bridge exception: %s", e.what());
00146 return;
00147 }
00148
00149
00150 if (cv_ptr->image.rows > 110 && cv_ptr->image.cols > 110)
00151 cv::circle(cv_ptr->image, cv::Point(cv_ptr->image.cols / 2, cv_ptr->image.rows / 2), 100, CV_RGB(255, 0, 0));
00152
00153 if (debug_view_)
00154 {
00155
00156 cv::imshow(OPENCV_WINDOW, cv_ptr->image);
00157 cv::waitKey(3);
00158 }
00159
00160
00161 #ifndef CV_BRIDGE_COMPRESSED_IMAGE_IS_NOT_SUPPORTED
00162 image_pub_.publish(cv_ptr->toCompressedImageMsg());
00163 #else
00164 image_pub_.publish(toCompressedImageMsg(cv_ptr));
00165 #endif
00166 }
00167 #ifdef CV_BRIDGE_COMPRESSED_IMAGE_IS_NOT_SUPPORTED
00168 sensor_msgs::CompressedImage toCompressedImageMsg(cv_bridge::CvImagePtr cv_ptr) const
00169 {
00170 sensor_msgs::CompressedImage ros_image;
00171 const std::string dst_format = std::string();
00172 ros_image.header = cv_ptr->header;
00173 cv::Mat image;
00174 if (cv_ptr->encoding != sensor_msgs::image_encodings::BGR8)
00175 {
00176 cv_bridge::CvImagePtr tempThis = boost::make_shared<cv_bridge::CvImage>(*cv_ptr);
00177 cv_bridge::CvImagePtr temp = cv_bridge::cvtColor(tempThis, sensor_msgs::image_encodings::BGR8);
00178 cv_ptr->image = temp->image;
00179 }
00180 else
00181 {
00182 image = cv_ptr->image;
00183 }
00184 std::vector<uchar> buf;
00185 if (dst_format.empty() || dst_format == "jpg")
00186 {
00187 ros_image.format = "jpg";
00188 cv::imencode(".jpg", image, buf);
00189 }
00190
00191 if (dst_format == "png")
00192 {
00193 ros_image.format = "png";
00194 cv::imencode(".png", image, buf);
00195 }
00196
00197
00198
00199
00200 if (dst_format == "jp2")
00201 {
00202 ros_image.format = "jp2";
00203 cv::imencode(".jp2", image, buf);
00204 }
00205
00206 if (dst_format == "bmp")
00207 {
00208 ros_image.format = "bmp";
00209 cv::imencode(".bmp", image, buf);
00210 }
00211
00212 if (dst_format == "tif")
00213 {
00214 ros_image.format = "tif";
00215 cv::imencode(".tif", image, buf);
00216 }
00217
00218 ros_image.data = buf;
00219 return ros_image;
00220 }
00221 #endif
00222 };
00223
00224 }
00225
00226 class SimpleCompressedExampleNodelet : public nodelet::Nodelet
00227 {
00228 public:
00229 virtual void onInit()
00230 {
00231 simple_compressed_example::ImageConverter ic;
00232 ros::spin();
00233 }
00234 };
00235
00236 }
00237
00238 namespace simple_compressed_example
00239 {
00240 class SimpleCompressedExampleNodelet : public opencv_apps::SimpleCompressedExampleNodelet
00241 {
00242 public:
00243 virtual void onInit()
00244 {
00245 ROS_WARN("DeprecationWarning: Nodelet simple_compressed_example/simple_compressed_example is deprecated, "
00246 "and renamed to opencv_apps/simple_compressed_example.");
00247 opencv_apps::SimpleCompressedExampleNodelet::onInit();
00248 }
00249 };
00250 }
00251
00252 #include <pluginlib/class_list_macros.h>
00253 PLUGINLIB_EXPORT_CLASS(opencv_apps::SimpleCompressedExampleNodelet, nodelet::Nodelet);
00254 PLUGINLIB_EXPORT_CLASS(simple_compressed_example::SimpleCompressedExampleNodelet, nodelet::Nodelet);