22 #include <asr_halcon_bridge/halcon_image.h> 23 #include <boost/make_shared.hpp> 30 return boost::regex_match(to_check.c_str(), what, regex);
34 std::string
trim(std::string input) {
35 input.erase(0,input.find_first_not_of(
" "));
36 input.erase(input.find_last_not_of(
" ")+1);
40 wxBitmap*
createBitmap(
const sensor_msgs::Image::ConstPtr& msg,
int width,
int height) {
41 wxImage img(msg->width, msg->height);
42 int bpp = msg->step / msg->width;
43 if (msg->encoding ==
"bgr8") {
44 for (
int i = 0; i < img.GetHeight(); i++) {
45 for (
int j = 0; j < img.GetWidth(); j++) {
47 msg->data[i * msg->step + bpp * j + 2],
48 msg->data[i * msg->step + bpp * j + 1],
49 msg->data[i * msg->step + bpp * j]);
52 }
else if (msg->encoding ==
"mono8") {
53 for (
int i = 0; i < img.GetHeight(); i++) {
54 for (
int j = 0; j < img.GetWidth(); j++) {
56 msg->data[i * msg->step + bpp * j],
57 msg->data[i * msg->step + bpp * j],
58 msg->data[i * msg->step + bpp * j]);
61 }
else if (msg->encoding ==
"rgb8") {
62 unsigned char *data = (
unsigned char*)(&msg->data[0]);
63 img = wxImage(msg->width, msg->height, data,
true);
65 img = img.Scale(width, height);
66 wxBitmap* image =
new wxBitmap(img);
71 wxBitmap*
createBitmap(HalconCpp::HImage image,
int width,
int height)
73 halcon_bridge::HalconImagePtr ptr = boost::make_shared<halcon_bridge::HalconImage>();
74 if (image.CountChannels() == 1) {
75 ptr->encoding =
"mono8";
77 ptr->encoding =
"rgb8";
79 ptr->image =
new HalconCpp::HImage();
81 sensor_msgs::ImagePtr imgptr = ptr->toImageMsg();
88 std::string
string = std::string(input.mb_str());
90 char cur = *
string.rbegin();
92 string.resize(
string.size() - 1);
93 cur = *
string.rbegin();
98 return wxString(
string.c_str(), wxConvUTF8);
103 void get_all_files_with_ext(
const boost::filesystem::path& root,
const std::string& ext, std::vector<boost::filesystem::path>& ret)
105 if(!boost::filesystem::exists(root) || !boost::filesystem::is_directory(root))
return;
107 boost::filesystem::recursive_directory_iterator it(root);
108 boost::filesystem::recursive_directory_iterator endit;
112 if(boost::filesystem::is_regular_file(*it) && it->path().extension() == ext) ret.push_back(it->path().filename());
118 HalconCpp::HImage
drawBoundingBox(HalconCpp::HImage image, std::vector<Eigen::Vector2i> corner_points)
120 int max_expand = image.Width();
121 if (image.Width() < image.Height()) {
122 max_expand = image.Height();
124 int scale_factor = max_expand / 100;
125 int BOX_BORDER_SIZE = 8;
126 int CORNER_RADIUS = 3;
127 if (scale_factor > 1) {
128 BOX_BORDER_SIZE = BOX_BORDER_SIZE * (1.f + (scale_factor / 10.f));
129 CORNER_RADIUS = CORNER_RADIUS * (1.f + (scale_factor / 10.f));
131 HalconCpp::HTuple color(255);
132 if (image.CountChannels() > 1) {
136 HalconCpp::HTuple rows, columns;
137 for (
unsigned int i = 0; i < corner_points.size(); i++) {
138 rows.Append(corner_points.at(i)[1]);
139 columns.Append(corner_points.at(i)[0]);
141 if (corner_points.size() == 4) {
142 HalconCpp::HTuple rows_outer, columns_outer;
143 rows_outer.Append(rows[0] - BOX_BORDER_SIZE);
144 rows_outer.Append(rows[1] - BOX_BORDER_SIZE);
145 rows_outer.Append(rows[2] + BOX_BORDER_SIZE);
146 rows_outer.Append(rows[3] + BOX_BORDER_SIZE);
147 columns_outer.Append(columns[0] - BOX_BORDER_SIZE);
148 columns_outer.Append(columns[1] + BOX_BORDER_SIZE);
149 columns_outer.Append(columns[2] + BOX_BORDER_SIZE);
150 columns_outer.Append(columns[3] - BOX_BORDER_SIZE);
151 HalconCpp::HRegion box_points;
152 box_points.GenRegionPolygonFilled(rows, columns);
154 HalconCpp::HRegion box_points_outer;
155 box_points_outer.GenRegionPolygonFilled(rows_outer, columns_outer);
157 box_points = box_points_outer.Difference(box_points);
158 image = box_points.PaintRegion(image, color, HalconCpp::HTuple(
"fill"));
159 }
else if (corner_points.size() > 0) {
160 HalconCpp::HTuple radius;
161 radius = HalconCpp::HTuple::TupleGenConst(rows.Length(), CORNER_RADIUS);
162 HalconCpp::HRegion box_points;
163 box_points.GenCircle(rows, columns, radius);
164 image = box_points.PaintRegion(image, color, HalconCpp::HTuple(
"fill"));
wxString trimDoubleString(wxString input)
Formats the given string by removing fractional zeros at the end of it.
void get_all_files_with_ext(const boost::filesystem::path &root, const std::string &ext, std::vector< boost::filesystem::path > &ret)
Gets all files in a directory with a specific extension.
bool check_string_redex(std::string to_check, boost::regex regex)
Checks a string with the given regex.
wxBitmap * createBitmap(const sensor_msgs::Image::ConstPtr &msg, int width, int height)
Converts a ros-image-message to a bitmap-file used by wxwidgets.
std::string trim(std::string input)
Removes spaces from the beginning and end of the given string.
HalconCpp::HImage drawBoundingBox(HalconCpp::HImage image, std::vector< Eigen::Vector2i > corner_points)
Draws a bounding box on the given image with the also given corner-points.