Create_Output_Files_Dialog.cpp
Go to the documentation of this file.
1 
22 #include <rapidxml.hpp>
23 #include <rapidxml_print.hpp>
24 #include <rapidxml_utils.hpp>
25 #include <boost/filesystem.hpp>
26 #include <boost/lexical_cast.hpp>
27 #include <boost/thread.hpp>
28 #include <fstream>
29 #include <ros/package.h>
31 
32 
34 {
35 
36  boost::filesystem::path output_path(ros::package::getPath("asr_descriptor_surface_based_recognition") + OUTPUT_FOLDER + "/" + object_params.at(0) + "/");
37  boost::filesystem::path input_path(ros::package::getPath("asr_descriptor_surface_based_recognition") + INPUT_FOLDER + "/");
38  boost::filesystem::create_directory(output_path);
39 
40  std::ofstream logFile;
41  std::string log_filename = output_path.string() + "log.txt";
42  logFile.open (log_filename.c_str());
43  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Start creation.\n";
44 
45 
46  rapidxml::xml_document<> doc;
47  rapidxml::xml_node<>* decl = doc.allocate_node(rapidxml::node_declaration);
48  decl->append_attribute(doc.allocate_attribute("version", "1.0"));
49  decl->append_attribute(doc.allocate_attribute("encoding", "utf-8"));
50  doc.append_node(decl);
51 
52  rapidxml::xml_node<>* root = doc.allocate_node(rapidxml::node_element, "object");
53  doc.append_node(root);
54 
55  rapidxml::xml_node<>* node_name = doc.allocate_node(rapidxml::node_element, "name");
56  node_name->value(object_params.at(0).c_str());
57  root->append_node(node_name);
58 
59  rapidxml::xml_node<>* node_surface_mdl = doc.allocate_node(rapidxml::node_element, "surface_model");
60  std::string surface_mdl_name = object_params.at(0) + "_surfaceMdl.sfm";
61  node_surface_mdl->value(surface_mdl_name.c_str());
62  root->append_node(node_surface_mdl);
63 
64  rapidxml::xml_node<>* node_mesh = doc.allocate_node(rapidxml::node_element, "mesh");
65  node_mesh->value(object_params.at(2).c_str());
66  root->append_node(node_mesh);
67 
68  rapidxml::xml_node<>* node_rotation_type = doc.allocate_node(rapidxml::node_element, "rotation_model_type");
69  std::string rot_type = "0";
70  if (object_params.at(3) == ROTATIONTYPE_CYLINDER) { rot_type = "1";}
71  if (object_params.at(3) == ROTATIONTYPE_SPHERE) { rot_type = "2";}
72  node_rotation_type->value(rot_type.c_str());
73  root->append_node(node_rotation_type);
74 
75  rapidxml::xml_node<>* node_orientation = doc.allocate_node(rapidxml::node_element, "model_orientation");
76  std::string orientation = object_params.at(4) + ", " + object_params.at(5) + ", " + object_params.at(6);
77  node_orientation->value(orientation.c_str());
78  root->append_node(node_orientation);
79 
80  rapidxml::xml_node<>* node_diameter = doc.allocate_node(rapidxml::node_element, "diameter");
81  node_diameter->value(object_params.at(7).c_str());
82  root->append_node(node_diameter);
83 
84  rapidxml::xml_node<>* node_score3D = doc.allocate_node(rapidxml::node_element, "score3D");
85  node_score3D->value(object_params.at(8).c_str());
86  root->append_node(node_score3D);
87 
88  rapidxml::xml_node<>* node_desc_models = doc.allocate_node(rapidxml::node_element, "descriptor_models");
89 
90  for (unsigned int i = 0; i < views.size(); i++) {
91 
92  rapidxml::xml_node<>* node_desc_model = doc.allocate_node(rapidxml::node_element, "descriptor_model");
93 
94  rapidxml::xml_node<>* node_desc_model_name = doc.allocate_node(rapidxml::node_element, "name");
95  std::string desc_model_name = object_params.at(0) + "_view_" + boost::lexical_cast<std::string>(i + 1) + ".dsm";
96 
97  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Creating descriptor model (" << desc_model_name << ") with params: depth = " << views.at(i).getDepth() << ", fern-number = " << views.at(i).getNumberFerns() << ", patch-size = " << views.at(i).getPatchSize() << ", min-scale = " << views.at(i).getMinScale() << ", max-scale = " << views.at(i).getMaxScale() << "\n";
98 
99  node_desc_model_name->value(doc.allocate_string(desc_model_name.c_str()));
100  node_desc_model->append_node(node_desc_model_name);
101 
102  std::string view_image_name = object_params.at(0) + "_view_" + boost::lexical_cast<std::string>(i + 1) + ".png";
103  try {
104  //create desc model
105  HalconCpp::HImage img = views.at(i).getImage();
106  if (!(views.at(i).getUseColor())) {
107  img = img.Rgb1ToGray();
108  }
109  img.WriteImage("png", 0, (output_path.string() + view_image_name).c_str());
110  HalconCpp::HTuple descparamname("depth");
111  descparamname.Append("number_ferns");
112  descparamname.Append("patch_size");
113  descparamname.Append("max_scale");
114  descparamname.Append("min_scale");
115  HalconCpp::HTuple descparamvalue(views.at(i).getDepth());
116  descparamvalue.Append(views.at(i).getNumberFerns());
117  descparamvalue.Append(views.at(i).getPatchSize());
118  descparamvalue.Append(views.at(i).getMaxScale());
119  descparamvalue.Append(views.at(i).getMinScale());
120  img.CreateUncalibDescriptorModel("harris_binomial", HalconCpp::HTuple(), HalconCpp::HTuple(), descparamname, descparamvalue, 42).WriteDescriptorModel((output_path.string() + desc_model_name).c_str());
121  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Descriptor model creation successful (" << desc_model_name << ").\n";
122  } catch(HalconCpp::HException exc) {
123  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Could not create descriptor model (" << desc_model_name << "), Error msg: " << exc.ErrorText() << ".\n";
124  success = false;
125  continue;
126  }
127 
128 
129 
130  rapidxml::xml_node<>* node_desc_model_orientation = doc.allocate_node(rapidxml::node_element, "view_orientation");
131  std::string view_or_0 = boost::lexical_cast<std::string>(views.at(i).getOrientation()[0]);
132  std::string view_or_1 = boost::lexical_cast<std::string>(views.at(i).getOrientation()[1]);
133  std::string view_or_2 = boost::lexical_cast<std::string>(views.at(i).getOrientation()[2]);
134  std::replace(view_or_0.begin(), view_or_0.end(), ',', '.');
135  std::replace(view_or_1.begin(), view_or_1.end(), ',', '.');
136  std::replace(view_or_2.begin(), view_or_2.end(), ',', '.');
137  std::string desc_model_orientation = view_or_0 + ", " + view_or_1 + ", " + view_or_2;
138 
139  node_desc_model_orientation->value(doc.allocate_string(desc_model_orientation.c_str()));
140  node_desc_model->append_node(node_desc_model_orientation);
141 
142  rapidxml::xml_node<>* node_desc_model_score2D = doc.allocate_node(rapidxml::node_element, "score2D");
143  std::string desc_model_score2D = boost::lexical_cast<std::string>(views.at(i).getScore2D());
144  std::replace(desc_model_score2D.begin(), desc_model_score2D.end(), ',', '.');
145  node_desc_model_score2D->value(doc.allocate_string(desc_model_score2D.c_str()));
146  node_desc_model->append_node(node_desc_model_score2D);
147 
148  rapidxml::xml_node<>* node_desc_model_use_color = doc.allocate_node(rapidxml::node_element, "use_color");
149  std::string desc_model_use_color = boost::lexical_cast<std::string>(views.at(i).getUseColor());
150  node_desc_model_use_color->value(doc.allocate_string(desc_model_use_color.c_str()));
151  node_desc_model->append_node(node_desc_model_use_color);
152 
153  rapidxml::xml_node<>* node_desc_model_vertical_offset = doc.allocate_node(rapidxml::node_element, "vertical_texture_offset");
154  std::string desc_model_vertical_offset = boost::lexical_cast<std::string>(views.at(i).getVerticalOffset());
155  node_desc_model_vertical_offset->value(doc.allocate_string(desc_model_vertical_offset.c_str()));
156  node_desc_model->append_node(node_desc_model_vertical_offset);
157 
158  rapidxml::xml_node<>* node_desc_model_horizontal_offset = doc.allocate_node(rapidxml::node_element, "horizontal_texture_offset");
159  std::string desc_model_horizontal_offset = boost::lexical_cast<std::string>(views.at(i).getHorizontalOffset());
160  node_desc_model_horizontal_offset->value(doc.allocate_string(desc_model_horizontal_offset.c_str()));
161  node_desc_model->append_node(node_desc_model_horizontal_offset);
162 
163  rapidxml::xml_node<>* node_desc_model_invertible = doc.allocate_node(rapidxml::node_element, "invertible");
164  std::string desc_model_invertible = boost::lexical_cast<std::string>(views.at(i).getIsInvertible());
165  node_desc_model_invertible->value(doc.allocate_string(desc_model_invertible.c_str()));
166  node_desc_model->append_node(node_desc_model_invertible);
167 
168  rapidxml::xml_node<>* node_desc_model_bounding_box = doc.allocate_node(rapidxml::node_element, "bounding_box");
169  for (unsigned int j = 0; j < views.at(i).getBoxCorners().size(); j++) {
170  rapidxml::xml_node<>* node_desc_model_bounding_box_corner = doc.allocate_node(rapidxml::node_element, "corner_point");
171  std::string point_vector = boost::lexical_cast<std::string>((int)(views.at(i).getBoxCorners().at(j)[0] - 0.5 * (int)views.at(i).getImage().Width())) + ", " + boost::lexical_cast<std::string>((int)(views.at(i).getBoxCorners().at(j)[1] - 0.5 * (int)views.at(i).getImage().Height()));
172  node_desc_model_bounding_box_corner->value(doc.allocate_string(point_vector.c_str()));
173  node_desc_model_bounding_box->append_node(node_desc_model_bounding_box_corner);
174  }
175 
176  node_desc_model->append_node(node_desc_model_bounding_box);
177 
178 
179  if (views.at(i).getRotationType() != ROTATIONTYPE_NO_ROTATION) {
180  rapidxml::xml_node<>* node_desc_model_axes = doc.allocate_node(rapidxml::node_element, "rotation_axes");
181 
182  rapidxml::xml_node<>* node_desc_model_axis_1 = doc.allocate_node(rapidxml::node_element, "axis_1");
183  std::string axis_1_x =boost::lexical_cast<std::string>(views.at(i).getAxis1()[0]);
184  std::string axis_1_y =boost::lexical_cast<std::string>(views.at(i).getAxis1()[1]);
185  std::string axis_1_z =boost::lexical_cast<std::string>(views.at(i).getAxis1()[2]);
186  std::replace(axis_1_x.begin(), axis_1_x.end(), ',', '.');
187  std::replace(axis_1_y.begin(), axis_1_y.end(), ',', '.');
188  std::replace(axis_1_z.begin(), axis_1_z.end(), ',', '.');
189 
190  std::string desc_model_axis_1 = axis_1_x + ", " + axis_1_y + ", " + axis_1_z;
191  node_desc_model_axis_1->value(doc.allocate_string(desc_model_axis_1.c_str()));
192  std::string desc_model_axis_1_angle = boost::lexical_cast<std::string>(views.at(i).getAxis1Angle());
193  std::replace(desc_model_axis_1_angle.begin(), desc_model_axis_1_angle.end(), ',', '.');
194 
195  rapidxml::xml_attribute<> *axis_1_angle_attr = doc.allocate_attribute("angle", doc.allocate_string(desc_model_axis_1_angle.c_str()));
196  node_desc_model_axis_1->append_attribute(axis_1_angle_attr);
197  node_desc_model_axes->append_node(node_desc_model_axis_1);
198 
199  if (views.at(i).getRotationType() == ROTATIONTYPE_SPHERE) {
200  rapidxml::xml_node<>* node_desc_model_axis_2 = doc.allocate_node(rapidxml::node_element, "axis_2");
201  std::string axis_2_x =boost::lexical_cast<std::string>(views.at(i).getAxis2()[0]);
202  std::string axis_2_y =boost::lexical_cast<std::string>(views.at(i).getAxis2()[1]);
203  std::string axis_2_z =boost::lexical_cast<std::string>(views.at(i).getAxis2()[2]);
204  std::replace(axis_2_x.begin(), axis_2_x.end(), ',', '.');
205  std::replace(axis_2_y.begin(), axis_2_y.end(), ',', '.');
206  std::replace(axis_2_z.begin(), axis_2_z.end(), ',', '.');
207  std::string desc_model_axis_2 = axis_2_x + ", " + axis_2_y + ", " + axis_2_z;
208  node_desc_model_axis_2->value(doc.allocate_string(desc_model_axis_2.c_str()));
209  std::string desc_model_axis_2_angle = boost::lexical_cast<std::string>(views.at(i).getAxis2Angle());
210  std::replace(desc_model_axis_2_angle.begin(), desc_model_axis_2_angle.end(), ',', '.');
211  rapidxml::xml_attribute<> *axis_2_angle_attr = doc.allocate_attribute("angle", doc.allocate_string(desc_model_axis_2_angle.c_str()));
212  node_desc_model_axis_2->append_attribute(axis_2_angle_attr);
213  node_desc_model_axes->append_node(node_desc_model_axis_2);
214  }
215 
216  node_desc_model->append_node(node_desc_model_axes);
217  }
218  node_desc_models->append_node(node_desc_model);
219 
220  progress_bar->SetValue(progress_bar->GetValue() + 1);
221  }
222  root->append_node(node_desc_models);
223 
224  std::string filename = object_params.at(0) + ".xml";
225  filename = output_path.string() + filename;
226  std::ofstream file_stored(filename.c_str());
227  file_stored << doc;
228  file_stored.close();
229  doc.clear();
230 
231  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "XML-file successfully created.\n";
232 
233  progress_bar->SetValue(progress_bar->GetValue() + 1);
234 
235  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Creating surface model.\n";
236  try {
237  std::string object_model_path = input_path.string() + object_params.at(1);
238  HalconCpp::HObjectModel3D model;
239  model.ReadObjectModel3d(object_model_path.c_str(), "mm", HalconCpp::HTuple(), HalconCpp::HTuple());
240  HalconCpp::HSurfaceModel surface_mdl = model.CreateSurfaceModel(0.035, HalconCpp::HTuple(), HalconCpp::HTuple());
241  surface_mdl.WriteSurfaceModel((output_path.string() + object_params.at(0) + "_surfaceMdl.sfm").c_str());
242  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Surface model successfully created.\n";
243  } catch (HalconCpp::HException exc) {
244  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Surface model could not be created, error msg: " << exc.ErrorText() << ".\n";
245  success = false;
246  }
247  progress_bar->SetValue(progress_bar->GetValue() + 1);
248 
249  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Copying mesh file.\n";
250  std::string mesh_path = input_path.string() + object_params.at(2);
251  std::string mesh_destination_path = output_path.string() + object_params.at(2);
252  try {
253  boost::filesystem::copy_file(mesh_path, mesh_destination_path, boost::filesystem::copy_option::overwrite_if_exists);
254  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Mesh file successfully copied.\n";
255  } catch (boost::filesystem::filesystem_error err) {
256  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Could not copy mesh file.\n";
257  success = false;
258  }
259  progress_bar->SetValue(progress_bar->GetValue() + 1);
260 
261  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Copying texture-file of mesh.\n";
262  try {
263  rapidxml::file<> xmlFile(mesh_path.c_str());
264  rapidxml::xml_document<> mesh_doc;
265  mesh_doc.parse<0>(xmlFile.data());
266  if ((mesh_doc.first_node()) && (mesh_doc.first_node()->first_node("library_images")) && (mesh_doc.first_node()->first_node("library_images")->first_node("image")) && mesh_doc.first_node()->first_node("library_images")->first_node("image")->first_node("init_from")) {
267  std::string texture_name = mesh_doc.first_node()->first_node("library_images")->first_node("image")->first_node("init_from")->value();
268  std::string texture_path = input_path.string() + texture_name;
269  std::string texture_destination_path = output_path.string() + texture_name;
270  boost::filesystem::copy_file(texture_path, texture_destination_path, boost::filesystem::copy_option::overwrite_if_exists);
271  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Texture file successfully copied.\n";
272  } else {
273  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Could not copy mesh file.\n";
274  success = false;
275  }
276  } catch(boost::filesystem::filesystem_error err) {
277  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Could not copy mesh file.\n";
278  success = false;
279  } catch (std::runtime_error err) {
280  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Could not copy mesh file.\n";
281  success = false;
282  }
283  progress_bar->SetValue(progress_bar->GetValue() + 1);
284 
285 
286 
287  if (progress_bar->GetValue() < progress_bar->GetRange()) {
288  progress_bar->SetValue(progress_bar->GetRange());
289  }
290  logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Output files creation done.\n";
291  logFile.close();
292  button_done->Enable();
293 
294 }
295 
297  : Create_Output_Files_Dialog_Base(parent_dialog),
298  views(parent_dialog->getViews()),
299  object_params(parent_dialog->getObjectParameters()),
300  success(true)
301 {
302  button_done->Enable(false);
303  progress_bar->SetRange(4 + views.size());
304 
305  boost::thread create_files_thread(boost::bind(&CreateOutputFilesDialog::createOutputFiles, this));
306 }
307 
309 {
310  if (success) {
311  EndModal(wxID_OK);
312  } else {
313  EndModal(wxID_CANCEL);
314  }
315  Destroy();
316 }
317 
318 void CreateOutputFilesDialog::onDialogClose(wxCloseEvent &event)
319 {
320 
321 }
root
filename
void createOutputFiles()
Creates the output files with the set parameters.
const std::string ROTATIONTYPE_CYLINDER
Definition: Utils.h:40
const std::string ROTATIONTYPE_SPHERE
Definition: Utils.h:43
const std::string ROTATIONTYPE_NO_ROTATION
Definition: Utils.h:37
ROSLIB_DECL std::string getPath(const std::string &package_name)
void onButtonDoneClicked(wxCommandEvent &event)
CreateOutputFilesDialog(DescModelsDialog *parent_dialog)
Constructor of this class.
static Time now()
std::vector< std::string > object_params
std::vector< ViewParamsWrapper > views
void onDialogClose(wxCloseEvent &event)
const std::string INPUT_FOLDER
Definition: Utils.h:46
const std::string OUTPUT_FOLDER
Definition: Utils.h:49


asr_descriptor_surface_based_recognition
Author(s): Allgeyer Tobias, Hutmacher Robin, Meißner Pascal
autogenerated on Mon Dec 16 2019 03:31:15