39 #include <opencv2/core/core.hpp> 40 #include <opencv2/highgui/highgui.hpp> 52 return static_cast<double>(raw_value) / std::numeric_limits<T>::max();
60 info.
width = cv_img.cols;
64 unsigned int n_channels = cv_img.channels();
66 for (
unsigned int j = 0; j < info.
height; j++)
68 const T* row_ptr = cv_img.ptr<T>(j);
69 for (
unsigned int i = 0; i < info.
width; i++)
72 const T* col_ptr = row_ptr + i * n_channels;
73 for (
unsigned int k = 0; k < n_channels; ++k)
75 T raw_value = *(col_ptr + k);
90 cv::Mat cv_img = cv::imread(filepath, -1);
91 if (cv_img.data ==
nullptr)
93 std::string errmsg = std::string(
"failed to open image file \"") + filepath + std::string(
"\"");
94 throw std::runtime_error(errmsg);
97 int depth = cv_img.depth();
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);
109 throw std::runtime_error(
"Unsupported image");
122 const Pixel& pixel = image(index);
123 unsigned int max_channel = pixel.
channels.size();
124 if (max_channel == 4)
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));
148 double intensity = intensity_img(index);
155 costmap.
setValue(index, static_cast<unsigned char>(round(255 * intensity)));
162 const bool negate_param,
const double occ_th,
const double free_th,
const std::string& mode)
186 if (mode ==
"trinary")
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'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.
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
nav_grid::VectorNavGrid< Pixel > getImage(const std::string &filepath, bool flip_y_axis=true)
Load an image as a NavGrid of pixels.