Go to the documentation of this file.00001
00021 #include "descriptor_surface_based_trainer/Utils.h"
00022 #include <asr_halcon_bridge/halcon_image.h>
00023 #include <boost/make_shared.hpp>
00024
00025
00026
00027 bool check_string_redex(std::string to_check, boost::regex regex)
00028 {
00029 boost::cmatch what;
00030 return boost::regex_match(to_check.c_str(), what, regex);
00031 }
00032
00033
00034 std::string trim(std::string input) {
00035 input.erase(0,input.find_first_not_of(" "));
00036 input.erase(input.find_last_not_of(" ")+1);
00037 return input;
00038 }
00039
00040 wxBitmap* createBitmap(const sensor_msgs::Image::ConstPtr& msg, int width, int height) {
00041 wxImage img(msg->width, msg->height);
00042 int bpp = msg->step / msg->width;
00043 if (msg->encoding == "bgr8") {
00044 for (int i = 0; i < img.GetHeight(); i++) {
00045 for (int j = 0; j < img.GetWidth(); j++) {
00046 img.SetRGB(j, i,
00047 msg->data[i * msg->step + bpp * j + 2],
00048 msg->data[i * msg->step + bpp * j + 1],
00049 msg->data[i * msg->step + bpp * j]);
00050 }
00051 }
00052 } else if (msg->encoding == "mono8") {
00053 for (int i = 0; i < img.GetHeight(); i++) {
00054 for (int j = 0; j < img.GetWidth(); j++) {
00055 img.SetRGB(j, i,
00056 msg->data[i * msg->step + bpp * j],
00057 msg->data[i * msg->step + bpp * j],
00058 msg->data[i * msg->step + bpp * j]);
00059 }
00060 }
00061 } else if (msg->encoding == "rgb8") {
00062 unsigned char *data = (unsigned char*)(&msg->data[0]);
00063 img = wxImage(msg->width, msg->height, data, true);
00064 }
00065 img = img.Scale(width, height);
00066 wxBitmap* image = new wxBitmap(img);
00067 return image;
00068
00069 }
00070
00071 wxBitmap* createBitmap(HalconCpp::HImage image, int width, int height)
00072 {
00073 halcon_bridge::HalconImagePtr ptr = boost::make_shared<halcon_bridge::HalconImage>();
00074 if (image.CountChannels() == 1) {
00075 ptr->encoding = "mono8";
00076 } else {
00077 ptr->encoding = "rgb8";
00078 }
00079 ptr->image = new HalconCpp::HImage();
00080 *ptr->image = image;
00081 sensor_msgs::ImagePtr imgptr = ptr->toImageMsg();
00082 return createBitmap(imgptr, width, height);
00083 }
00084
00085
00086 wxString trimDoubleString(wxString input)
00087 {
00088 std::string string = std::string(input.mb_str());
00089 if (check_string_redex(string, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)$"))) {
00090 char cur = *string.rbegin();
00091 while (cur == '0') {
00092 string.resize(string.size() - 1);
00093 cur = *string.rbegin();
00094 }
00095 if (cur == '.') {
00096 string += '0';
00097 }
00098 return wxString(string.c_str(), wxConvUTF8);
00099 }
00100 return input;
00101 }
00102
00103 void get_all_files_with_ext(const boost::filesystem::path& root, const std::string& ext, std::vector<boost::filesystem::path>& ret)
00104 {
00105 if(!boost::filesystem::exists(root) || !boost::filesystem::is_directory(root)) return;
00106
00107 boost::filesystem::recursive_directory_iterator it(root);
00108 boost::filesystem::recursive_directory_iterator endit;
00109
00110 while(it != endit)
00111 {
00112 if(boost::filesystem::is_regular_file(*it) && it->path().extension() == ext) ret.push_back(it->path().filename());
00113 ++it;
00114 }
00115
00116 }
00117
00118 HalconCpp::HImage drawBoundingBox(HalconCpp::HImage image, std::vector<Eigen::Vector2i> corner_points)
00119 {
00120 int max_expand = image.Width();
00121 if (image.Width() < image.Height()) {
00122 max_expand = image.Height();
00123 }
00124 int scale_factor = max_expand / 100;
00125 int BOX_BORDER_SIZE = 8;
00126 int CORNER_RADIUS = 3;
00127 if (scale_factor > 1) {
00128 BOX_BORDER_SIZE = BOX_BORDER_SIZE * (1.f + (scale_factor / 10.f));
00129 CORNER_RADIUS = CORNER_RADIUS * (1.f + (scale_factor / 10.f));
00130 }
00131 HalconCpp::HTuple color(255);
00132 if (image.CountChannels() > 1) {
00133 color.Append(0);
00134 color.Append(0);
00135 }
00136 HalconCpp::HTuple rows, columns;
00137 for (unsigned int i = 0; i < corner_points.size(); i++) {
00138 rows.Append(corner_points.at(i)[1]);
00139 columns.Append(corner_points.at(i)[0]);
00140 }
00141 if (corner_points.size() == 4) {
00142 HalconCpp::HTuple rows_outer, columns_outer;
00143 rows_outer.Append(rows[0] - BOX_BORDER_SIZE);
00144 rows_outer.Append(rows[1] - BOX_BORDER_SIZE);
00145 rows_outer.Append(rows[2] + BOX_BORDER_SIZE);
00146 rows_outer.Append(rows[3] + BOX_BORDER_SIZE);
00147 columns_outer.Append(columns[0] - BOX_BORDER_SIZE);
00148 columns_outer.Append(columns[1] + BOX_BORDER_SIZE);
00149 columns_outer.Append(columns[2] + BOX_BORDER_SIZE);
00150 columns_outer.Append(columns[3] - BOX_BORDER_SIZE);
00151 HalconCpp::HRegion box_points;
00152 box_points.GenRegionPolygonFilled(rows, columns);
00153
00154 HalconCpp::HRegion box_points_outer;
00155 box_points_outer.GenRegionPolygonFilled(rows_outer, columns_outer);
00156
00157 box_points = box_points_outer.Difference(box_points);
00158 image = box_points.PaintRegion(image, color, HalconCpp::HTuple("fill"));
00159 } else if (corner_points.size() > 0) {
00160 HalconCpp::HTuple radius;
00161 radius = HalconCpp::HTuple::TupleGenConst(rows.Length(), CORNER_RADIUS);
00162 HalconCpp::HRegion box_points;
00163 box_points.GenCircle(rows, columns, radius);
00164 image = box_points.PaintRegion(image, color, HalconCpp::HTuple("fill"));
00165 }
00166
00167 return image;
00168 }