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 #include "image_proc/processor.h"
00035 #include <sensor_msgs/image_encodings.h>
00036 #include <ros/console.h>
00037
00038 namespace image_proc {
00039
00040 namespace enc = sensor_msgs::image_encodings;
00041
00042 bool Processor::process(const sensor_msgs::ImageConstPtr& raw_image,
00043 const image_geometry::PinholeCameraModel& model,
00044 ImageSet& output, int flags) const
00045 {
00046 static const int MONO_EITHER = MONO | RECT;
00047 static const int COLOR_EITHER = COLOR | RECT_COLOR;
00048 if (!(flags & ALL)) return true;
00049
00050
00051 const std::string& raw_encoding = raw_image->encoding;
00052 int raw_type = CV_8UC1;
00053 if (raw_encoding == enc::BGR8 || raw_encoding == enc::RGB8) {
00054 raw_type = CV_8UC3;
00055 output.color_encoding = raw_encoding;
00056 }
00057
00058 const cv::Mat raw(raw_image->height, raw_image->width, raw_type,
00059 const_cast<uint8_t*>(&raw_image->data[0]), raw_image->step);
00060
00062
00064
00065
00066 if (raw_encoding.find("bayer") != std::string::npos) {
00067
00069 int code = 0;
00070 if (raw_encoding == enc::BAYER_RGGB8)
00071 code = cv::COLOR_BayerBG2BGR;
00072 else if (raw_encoding == enc::BAYER_BGGR8)
00073 code = cv::COLOR_BayerRG2BGR;
00074 else if (raw_encoding == enc::BAYER_GBRG8)
00075 code = cv::COLOR_BayerGR2BGR;
00076 else if (raw_encoding == enc::BAYER_GRBG8)
00077 code = cv::COLOR_BayerGB2BGR;
00078 else {
00079 ROS_ERROR("[image_proc] Unsupported encoding '%s'", raw_encoding.c_str());
00080 return false;
00081 }
00082 cv::cvtColor(raw, output.color, code);
00083 output.color_encoding = enc::BGR8;
00084
00085 if (flags & MONO_EITHER)
00086 cv::cvtColor(output.color, output.mono, cv::COLOR_BGR2GRAY);
00087 }
00088
00089 else if (raw_type == CV_8UC3) {
00090 output.color = raw;
00091 if (flags & MONO_EITHER) {
00092 int code = (raw_encoding == enc::BGR8) ? cv::COLOR_BGR2GRAY : cv::COLOR_RGB2GRAY;
00093 cv::cvtColor(output.color, output.mono, code);
00094 }
00095 }
00096
00097 else if (raw_encoding == enc::MONO8) {
00098 output.mono = raw;
00099 if (flags & COLOR_EITHER) {
00100 output.color_encoding = enc::MONO8;
00101 output.color = raw;
00102 }
00103 }
00104
00105 else if (raw_encoding == enc::TYPE_8UC3) {
00106 ROS_ERROR("[image_proc] Ambiguous encoding '8UC3'. The camera driver "
00107 "should set the encoding to 'bgr8' or 'rgb8'.");
00108 return false;
00109 }
00110
00111 else {
00112 ROS_ERROR("[image_proc] Unsupported encoding '%s'", raw_encoding.c_str());
00113 return false;
00114 }
00115
00117
00119
00122 if (flags & RECT)
00123 model.rectifyImage(output.mono, output.rect, interpolation_);
00124 if (flags & RECT_COLOR)
00125 model.rectifyImage(output.color, output.rect_color, interpolation_);
00126
00127 return true;
00128 }
00129
00130 }