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
00035
00036 #include "jsk_recognition_utils/cv_utils.h"
00037 #include "jsk_recognition_utils/rgb_colors.h"
00038 #include <sensor_msgs/image_encodings.h>
00039
00040 namespace enc = sensor_msgs::image_encodings;
00041
00042 namespace jsk_recognition_utils
00043 {
00044 cv::MatND computeHistogram(const cv::Mat& input_image, int bin_size,
00045 float min_value, float max_value,
00046 const cv::Mat& mask_image)
00047 {
00048 int channels[] = {0};
00049 cv::MatND hist;
00050 int hist_size[] = {bin_size};
00051 float range[] = {min_value, max_value};
00052 const float* ranges[] = {range};
00053 cv::calcHist(&input_image, 1, channels, mask_image,
00054 hist, 1, hist_size,
00055 ranges, true, false);
00056 return hist;
00057 }
00058
00059 std::vector<jsk_recognition_msgs::HistogramWithRangeBin>
00060 cvMatNDToHistogramWithRangeBinArray(const cv::MatND& cv_hist, float min_value, float max_value)
00061 {
00062 std::vector<jsk_recognition_msgs::HistogramWithRangeBin> bins(cv_hist.total());
00063 const float bin_width = (max_value - min_value) / cv_hist.total();
00064 for (size_t i = 0; i < cv_hist.total(); i++) {
00065 const float left = i * bin_width + min_value;
00066 const float right = (i + 1) * bin_width + min_value;
00067 jsk_recognition_msgs::HistogramWithRangeBin bin;
00068 bin.min_value = left;
00069 bin.max_value = right;
00070 bin.count = cv_hist.at<float>(0, i);
00071 bins[i] = bin;
00072 }
00073 return bins;
00074 }
00075
00076 cv::MatND
00077 HistogramWithRangeBinArrayTocvMatND(
00078 const std::vector<jsk_recognition_msgs::HistogramWithRangeBin>& histogram)
00079 {
00080 cv::MatND ret(1, histogram.size(), CV_32F);
00081 for (size_t i = 0; i < histogram.size(); i++) {
00082 jsk_recognition_msgs::HistogramWithRangeBin bin = histogram[i];
00083 ret.at<float>(0, i) = bin.count;
00084 }
00085 return ret;
00086 }
00087
00088 bool compareHistogramWithRangeBin(const jsk_recognition_msgs::HistogramWithRangeBin& left,
00089 const jsk_recognition_msgs::HistogramWithRangeBin& right)
00090 {
00091 return left.count > right.count;
00092 }
00093
00094 void sortHistogramWithRangeBinArray(std::vector<jsk_recognition_msgs::HistogramWithRangeBin>& bins)
00095 {
00096 std::sort(bins.begin(), bins.end(), compareHistogramWithRangeBin);
00097 }
00098
00099 std::vector<jsk_recognition_msgs::HistogramWithRangeBin>
00100 topNHistogramWithRangeBins(const std::vector<jsk_recognition_msgs::HistogramWithRangeBin>& bins,
00101 double top_n_rate)
00102 {
00103 int sum = 0;
00104 for (size_t i = 0; i < bins.size(); i++) {
00105 sum += bins[i].count;
00106 }
00107 const int target_sum = sum * top_n_rate;
00108 std::vector<jsk_recognition_msgs::HistogramWithRangeBin> top_n_bins;
00109 top_n_bins.reserve(bins.size());
00110
00111 int current_sum = 0;
00112 for (size_t i = 0; i < bins.size(); i++) {
00113 jsk_recognition_msgs::HistogramWithRangeBin bin = bins[i];
00114 if (current_sum >= target_sum) {
00115 return top_n_bins;
00116 }
00117 top_n_bins.push_back(bin);
00118 current_sum += bins[i].count;
00119 }
00120 return top_n_bins;
00121 }
00122
00123 void
00124 drawHistogramWithRangeBin(cv::Mat& image,
00125 const jsk_recognition_msgs::HistogramWithRangeBin& bin,
00126 float min_width_value,
00127 float max_width_value,
00128 float max_height_value,
00129 cv::Scalar color)
00130 {
00131 if (max_height_value == 0.0) {
00132 return;
00133 }
00134 const int height = image.rows;
00135 const int width = image.cols;
00136 const int left = (bin.min_value - min_width_value) / (max_width_value - min_width_value) * width;
00137 const int right = (bin.max_value - min_width_value) / (max_width_value - min_width_value) * width;
00138 const int top = bin.count / max_height_value * height;
00139 if (bin.count == 0 || top == 0 || left == right || left < 0 || right >= width || top > height) {
00140 return;
00141 }
00142
00143 cv::rectangle(image, cv::Point(left, height), cv::Point(right, height - top),
00144 color, CV_FILLED);
00145 }
00146
00147 void labelToRGB(const cv::Mat src, cv::Mat& dst)
00148 {
00149 dst = cv::Mat::zeros(src.rows, src.cols, CV_8UC3);
00150 for (size_t j = 0; j < src.rows; ++j) {
00151 for (size_t i = 0; i < src.cols; ++i) {
00152 int label = src.at<int>(j, i);
00153 if (label == 0) {
00154 dst.at<cv::Vec3b>(j, i) = cv::Vec3b(0, 0, 0);
00155 }
00156 else {
00157 cv::Vec3d rgb = jsk_recognition_utils::getRGBColor(label);
00158 dst.at<cv::Vec3b>(j, i) = cv::Vec3b(int(rgb[0] * 255), int(rgb[1] * 255), int(rgb[2] * 255));
00159 }
00160 }
00161 }
00162 }
00163
00164 cv::Rect boundingRectOfMaskImage(const cv::Mat& image)
00165 {
00166 int min_x = image.cols;
00167 int min_y = image.rows;
00168 int max_x = 0;
00169 int max_y = 0;
00170 for (int j = 0; j < image.rows; j++) {
00171 for (int i = 0; i < image.cols; i++) {
00172 if (image.at<uchar>(j, i) != 0) {
00173 min_x = std::min(min_x, i);
00174 min_y = std::min(min_y, j);
00175 max_x = std::max(max_x, i);
00176 max_y = std::max(max_y, j);
00177 }
00178 }
00179 }
00180 return cv::Rect(min_x, min_y, std::max(max_x - min_x, 0), std::max(max_y - min_y, 0));
00181 }
00182
00183
00184 bool isBGR(const std::string& encoding)
00185 {
00186 return encoding == enc::BGR8 || encoding == enc::BGR16;
00187 }
00188
00189 bool isRGB(const std::string& encoding)
00190 {
00191 return encoding == enc::RGB8 || encoding == enc::RGB16;
00192 }
00193
00194 bool isBGRA(const std::string& encoding)
00195 {
00196 return encoding == enc::BGRA8 || encoding == enc::BGRA16;
00197 }
00198
00199 bool isRGBA(const std::string& encoding)
00200 {
00201 return encoding == enc::RGBA8 || encoding == enc::RGBA16;
00202 }
00203
00204 }