image_loader.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, Locus Robotics
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 copyright holder 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 HOLDER 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 
39 #include <opencv2/core/core.hpp>
40 #include <opencv2/highgui/highgui.hpp>
41 #include <limits>
42 #include <numeric>
43 #include <stdexcept>
44 #include <string>
45 #include <vector>
46 
47 namespace nav_grid_server
48 {
49 template <typename T>
50 double scaleNumber(T raw_value)
51 {
52  return static_cast<double>(raw_value) / std::numeric_limits<T>::max();
53 }
54 
55 template<typename T>
56 nav_grid::VectorNavGrid<Pixel> getImage(const cv::Mat& cv_img, bool flip_y_axis = false)
57 {
60  info.width = cv_img.cols;
61  info.height = cv_img.rows;
62  image.setInfo(info);
63 
64  unsigned int n_channels = cv_img.channels();
65 
66  for (unsigned int j = 0; j < info.height; j++)
67  {
68  const T* row_ptr = cv_img.ptr<T>(j);
69  for (unsigned int i = 0; i < info.width; i++)
70  {
71  Pixel pixel;
72  const T* col_ptr = row_ptr + i * n_channels;
73  for (unsigned int k = 0; k < n_channels; ++k)
74  {
75  T raw_value = *(col_ptr + k);
76  pixel.channels.push_back(scaleNumber(raw_value));
77  }
78 
79  if (flip_y_axis)
80  image.setValue(i, info.height - j - 1, pixel);
81  else
82  image.setValue(i, j, pixel);
83  }
84  }
85  return image;
86 }
87 
88 nav_grid::VectorNavGrid<Pixel> getImage(const std::string& filepath, bool flip_y_axis)
89 {
90  cv::Mat cv_img = cv::imread(filepath, -1); // -1 keeps the image in its native format, including alpha channel
91  if (cv_img.data == nullptr)
92  {
93  std::string errmsg = std::string("failed to open image file \"") + filepath + std::string("\"");
94  throw std::runtime_error(errmsg);
95  }
96 
97  int depth = cv_img.depth();
98  switch (depth)
99  {
100  case CV_8U: return getImage<unsigned char>(cv_img, flip_y_axis);
101  case CV_8S: return getImage<char>(cv_img, flip_y_axis);
102  case CV_16U: return getImage<uint16_t>(cv_img, flip_y_axis);
103  case CV_16S: return getImage<int16_t>(cv_img, flip_y_axis);
104  case CV_32S: return getImage<int>(cv_img, flip_y_axis);
105  case CV_32F: return getImage<float>(cv_img, flip_y_axis);
106  case CV_64F: return getImage<double>(cv_img, flip_y_axis);
107  default:
108  {
109  throw std::runtime_error("Unsupported image");
110  }
111  }
112 }
113 
114 nav_grid::VectorNavGrid<double> getImageIntensity(const std::string& filepath, bool flip_y_axis)
115 {
116  nav_grid::VectorNavGrid<Pixel> image = getImage(filepath, flip_y_axis);
117  nav_grid::NavGridInfo info = image.getInfo();
119  intensity.setInfo(info);
121  {
122  const Pixel& pixel = image(index);
123  unsigned int max_channel = pixel.channels.size();
124  if (max_channel == 4)
125  {
126  if (pixel.channels.back() == 0.0)
127  {
128  intensity.setValue(index, -1.0);
129  continue;
130  }
131  max_channel--;
132  }
133  double sum = std::accumulate(pixel.channels.begin(), pixel.channels.begin() + max_channel, 0.0);
134  intensity.setValue(index, sum / static_cast<double>(max_channel));
135  }
136 
137  return intensity;
138 }
139 
140 nav_grid::VectorNavGrid<unsigned char> getCostmapFromImage(const std::string& filepath, bool flip_y_axis)
141 {
142  nav_grid::VectorNavGrid<double> intensity_img = getImageIntensity(filepath, flip_y_axis);
143  nav_grid::NavGridInfo info = intensity_img.getInfo();
145  costmap.setInfo(info);
147  {
148  double intensity = intensity_img(index);
149  if (intensity < 0.0)
150  {
151  costmap.setValue(index, -1);
152  }
153  else
154  {
155  costmap.setValue(index, static_cast<unsigned char>(round(255 * intensity)));
156  }
157  }
158  return costmap;
159 }
160 
161 nav_grid::VectorNavGrid<unsigned char> classicLoadMapFromFile(const std::string& filepath, const double resolution,
162  const bool negate_param, const double occ_th, const double free_th, const std::string& mode)
163 {
165  nav_grid::NavGridInfo full_info = costmap.getInfo();
166  full_info.resolution = resolution;
167  costmap.setInfo(full_info);
168 
169  if (mode == "raw")
170  {
171  // This line would have no effect, but you can run it if you really want to
172  // nav_grid_pub_sub::applyInterpretation(costmap, nav_grid_pub_sub::RAW);
173 
174  if (negate_param)
175  {
177  }
178  }
179  else
180  {
181  if (!negate_param)
182  {
184  }
185 
186  if (mode == "trinary")
188  else
190  }
191  return costmap;
192 }
193 
194 } // namespace nav_grid_server
nav_grid::VectorNavGrid< unsigned char > classicLoadMapFromFile(const std::string &filepath, const double resolution, const bool negate_param, const double occ_th, const double free_th, const std::string &mode)
Load an image from a file, mimicking map_server&#39;s loading style Resulting values are [0...
nav_grid::VectorNavGrid< unsigned char > getCostmapFromImage(const std::string &filepath, bool flip_y_axis=true)
Load an image from a file and return values [0, 255].
std::vector< unsigned char > pixelColoringInterpretation(const double free_threshold, const double occupied_threshold)
double scaleNumber(T raw_value)
std::vector< unsigned char > grayScaleInterpretation(const double free_threshold, const double occupied_threshold)
void setInfo(const NavGridInfo &new_info) override
Independent (i.e. not OpenCV) representation of a Pixel.
Definition: image_loader.h:49
void setValue(const unsigned int x, const unsigned int y, const T &value) override
static std::vector< unsigned char > NEGATE
void applyInterpretation(nav_grid::NavGrid< IntegralType > &grid, const std::vector< IntegralType > &cost_interpretation_table)
NavGridInfo getInfo() const
nav_grid::VectorNavGrid< double > getImageIntensity(const std::string &filepath, bool flip_y_axis=true)
Load an image from a file and return the image intensity at each pixel.
std::vector< double > channels
Definition: image_loader.h:52
nav_grid::VectorNavGrid< Pixel > getImage(const std::string &filepath, bool flip_y_axis=true)
Load an image as a NavGrid of pixels.


nav_grid_server
Author(s):
autogenerated on Sun Jan 10 2021 04:08:55