41 #include <sensor_msgs/CompressedImage.h>
48 #include <opencv2/highgui/highgui.hpp>
49 #include <opencv2/imgproc/imgproc.hpp>
51 #include <dynamic_reconfigure/server.h>
91 void imageCb(
const sensor_msgs::CompressedImageConstPtr& msg)
101 #ifndef CV_BRIDGE_COMPRESSED_IMAGE_IS_NOT_SUPPORTED
107 cv::Mat jpegData(1, msg->data.size(), CV_8UC1);
108 jpegData.data =
const_cast<uchar*
>(&msg->data[0]);
109 cv::InputArray data(jpegData);
110 cv::Mat image = cv::imdecode(data, cv::IMREAD_COLOR);
114 sensor_msgs::Image ros_image;
115 ros_image.header = msg->header;
116 ros_image.height = image.rows;
117 ros_image.width = image.cols;
119 ros_image.is_bigendian =
false;
120 ros_image.step = image.cols * image.elemSize();
121 size_t size = ros_image.step * image.rows;
122 ros_image.data.resize(size);
124 if (image.isContinuous())
126 memcpy((
char*)(&ros_image.data[0]), image.data, size);
131 uchar* ros_data_ptr = (uchar*)(&ros_image.data[0]);
132 uchar* cv_data_ptr = image.data;
133 for (
int i = 0; i < image.rows; ++i)
135 memcpy(ros_data_ptr, cv_data_ptr, ros_image.step);
136 ros_data_ptr += ros_image.step;
137 cv_data_ptr += image.step;
145 ROS_ERROR(
"cv_bridge exception: %s", e.what());
150 if (cv_ptr->image.rows > 110 && cv_ptr->image.cols > 110)
151 cv::circle(cv_ptr->image, cv::Point(cv_ptr->image.cols / 2, cv_ptr->image.rows / 2), 100, CV_RGB(255, 0, 0));
161 #ifndef CV_BRIDGE_COMPRESSED_IMAGE_IS_NOT_SUPPORTED
167 #ifdef CV_BRIDGE_COMPRESSED_IMAGE_IS_NOT_SUPPORTED
170 sensor_msgs::CompressedImage ros_image;
171 const std::string dst_format = std::string();
172 ros_image.header = cv_ptr->header;
178 cv_ptr->image = temp->image;
182 image = cv_ptr->image;
184 std::vector<uchar> buf;
185 if (dst_format.empty() || dst_format ==
"jpg")
187 ros_image.format =
"jpg";
188 cv::imencode(
".jpg", image, buf);
191 if (dst_format ==
"png")
193 ros_image.format =
"png";
194 cv::imencode(
".png", image, buf);
200 if (dst_format ==
"jp2")
202 ros_image.format =
"jp2";
203 cv::imencode(
".jp2", image, buf);
206 if (dst_format ==
"bmp")
208 ros_image.format =
"bmp";
209 cv::imencode(
".bmp", image, buf);
212 if (dst_format ==
"tif")
214 ros_image.format =
"tif";
215 cv::imencode(
".tif", image, buf);
218 ros_image.data = buf;
231 simple_compressed_example::ImageConverter ic;
245 ROS_WARN(
"DeprecationWarning: Nodelet simple_compressed_example/simple_compressed_example is deprecated, "
246 "and renamed to opencv_apps/simple_compressed_example.");
252 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H