processor.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 #include "image_proc/processor.h"
36 #include <ros/console.h>
37 
38 namespace image_proc {
39 
41 
42 bool Processor::process(const sensor_msgs::ImageConstPtr& raw_image,
44  ImageSet& output, int flags) const
45 {
46  static const int MONO_EITHER = MONO | RECT;
47  static const int COLOR_EITHER = COLOR | RECT_COLOR;
48  if (!(flags & ALL)) return true;
49 
50  // Check if raw_image is color
51  const std::string& raw_encoding = raw_image->encoding;
52  int raw_type = CV_8UC1;
53  if (raw_encoding == enc::BGR8 || raw_encoding == enc::RGB8) {
54  raw_type = CV_8UC3;
55  output.color_encoding = raw_encoding;
56  }
57  // Construct cv::Mat pointing to raw_image data
58  const cv::Mat raw(raw_image->height, raw_image->width, raw_type,
59  const_cast<uint8_t*>(&raw_image->data[0]), raw_image->step);
60 
62  // Construct colorized (unrectified) images from raw //
64 
65  // Bayer case
66  if (raw_encoding.find("bayer") != std::string::npos) {
67  // Convert to color BGR
69  int code = 0;
70  if (raw_encoding == enc::BAYER_RGGB8)
71  code = cv::COLOR_BayerBG2BGR;
72  else if (raw_encoding == enc::BAYER_BGGR8)
73  code = cv::COLOR_BayerRG2BGR;
74  else if (raw_encoding == enc::BAYER_GBRG8)
75  code = cv::COLOR_BayerGR2BGR;
76  else if (raw_encoding == enc::BAYER_GRBG8)
77  code = cv::COLOR_BayerGB2BGR;
78  else {
79  ROS_ERROR("[image_proc] Unsupported encoding '%s'", raw_encoding.c_str());
80  return false;
81  }
82  cv::cvtColor(raw, output.color, code);
83  output.color_encoding = enc::BGR8;
84 
85  if (flags & MONO_EITHER)
86  cv::cvtColor(output.color, output.mono, cv::COLOR_BGR2GRAY);
87  }
88  // Color case
89  else if (raw_type == CV_8UC3) {
90  output.color = raw;
91  if (flags & MONO_EITHER) {
92  int code = (raw_encoding == enc::BGR8) ? cv::COLOR_BGR2GRAY : cv::COLOR_RGB2GRAY;
93  cv::cvtColor(output.color, output.mono, code);
94  }
95  }
96  // Mono case
97  else if (raw_encoding == enc::MONO8) {
98  output.mono = raw;
99  if (flags & COLOR_EITHER) {
100  output.color_encoding = enc::MONO8;
101  output.color = raw;
102  }
103  }
104  // 8UC3 does not specify a color encoding. Is it BGR, RGB, HSV, XYZ, LUV...?
105  else if (raw_encoding == enc::TYPE_8UC3) {
106  ROS_ERROR("[image_proc] Ambiguous encoding '8UC3'. The camera driver "
107  "should set the encoding to 'bgr8' or 'rgb8'.");
108  return false;
109  }
110  // Something else we can't handle
111  else {
112  ROS_ERROR("[image_proc] Unsupported encoding '%s'", raw_encoding.c_str());
113  return false;
114  }
115 
117  // Construct rectified images from colorized images //
119 
122  if (flags & RECT)
123  model.rectifyImage(output.mono, output.rect, interpolation_);
124  if (flags & RECT_COLOR)
125  model.rectifyImage(output.color, output.rect_color, interpolation_);
126 
127  return true;
128 }
129 
130 } //namespace image_proc
sensor_msgs::image_encodings
image_encodings.h
image_geometry::PinholeCameraModel::rectifyImage
void rectifyImage(const cv::Mat &raw, cv::Mat &rectified, int interpolation=cv::INTER_LINEAR) const
image_proc::Processor::MONO
@ MONO
Definition: processor.h:95
image_proc::Processor::interpolation_
int interpolation_
Definition: processor.h:92
console.h
image_proc::Processor::RECT_COLOR
@ RECT_COLOR
Definition: processor.h:98
processor.h
image_proc::Processor::COLOR
@ COLOR
Definition: processor.h:97
image_proc::Processor::RECT
@ RECT
Definition: processor.h:96
image_proc::Processor::ALL
@ ALL
Definition: processor.h:99
image_proc
Definition: advertisement_checker.h:39
image_geometry::PinholeCameraModel
sensor_msgs::image_encodings::MONO8
const std::string MONO8
ROS_ERROR
#define ROS_ERROR(...)
image_proc::Processor::process
bool process(const sensor_msgs::ImageConstPtr &raw_image, const image_geometry::PinholeCameraModel &model, ImageSet &output, int flags=ALL) const
Definition: processor.cpp:74


image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Wed Jan 24 2024 03:57:17