Create_Output_Files_Dialog.cpp
Go to the documentation of this file.
00001 
00021 #include "descriptor_surface_based_trainer/Create_Output_Files_Dialog.h"
00022 #include <rapidxml.hpp>
00023 #include <rapidxml_print.hpp>
00024 #include <rapidxml_utils.hpp>
00025 #include <boost/filesystem.hpp>
00026 #include <boost/lexical_cast.hpp>
00027 #include <boost/thread.hpp>
00028 #include <fstream>
00029 #include <ros/package.h>
00030 #include "descriptor_surface_based_trainer/Utils.h"
00031 
00032 
00033 void CreateOutputFilesDialog::createOutputFiles()
00034 {
00035 
00036     boost::filesystem::path output_path(ros::package::getPath("asr_descriptor_surface_based_recognition") + OUTPUT_FOLDER + "/" + object_params.at(0) + "/");
00037     boost::filesystem::path input_path(ros::package::getPath("asr_descriptor_surface_based_recognition") + INPUT_FOLDER + "/");
00038     boost::filesystem::create_directory(output_path);
00039 
00040     std::ofstream logFile;
00041     std::string log_filename = output_path.string() + "log.txt";
00042     logFile.open (log_filename.c_str());
00043     logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Start creation.\n";
00044 
00045 
00046     rapidxml::xml_document<> doc;
00047     rapidxml::xml_node<>* decl = doc.allocate_node(rapidxml::node_declaration);
00048     decl->append_attribute(doc.allocate_attribute("version", "1.0"));
00049     decl->append_attribute(doc.allocate_attribute("encoding", "utf-8"));
00050     doc.append_node(decl);
00051 
00052     rapidxml::xml_node<>* root = doc.allocate_node(rapidxml::node_element, "object");
00053     doc.append_node(root);
00054 
00055     rapidxml::xml_node<>* node_name = doc.allocate_node(rapidxml::node_element, "name");
00056     node_name->value(object_params.at(0).c_str());
00057     root->append_node(node_name);
00058 
00059     rapidxml::xml_node<>* node_surface_mdl = doc.allocate_node(rapidxml::node_element, "surface_model");
00060     std::string surface_mdl_name = object_params.at(0) + "_surfaceMdl.sfm";
00061     node_surface_mdl->value(surface_mdl_name.c_str());
00062     root->append_node(node_surface_mdl);
00063 
00064     rapidxml::xml_node<>* node_mesh = doc.allocate_node(rapidxml::node_element, "mesh");
00065     node_mesh->value(object_params.at(2).c_str());
00066     root->append_node(node_mesh);
00067 
00068     rapidxml::xml_node<>* node_rotation_type = doc.allocate_node(rapidxml::node_element, "rotation_model_type");
00069     std::string rot_type = "0";
00070     if (object_params.at(3) == ROTATIONTYPE_CYLINDER) { rot_type = "1";}
00071     if (object_params.at(3) == ROTATIONTYPE_SPHERE) { rot_type = "2";}
00072     node_rotation_type->value(rot_type.c_str());
00073     root->append_node(node_rotation_type);
00074 
00075     rapidxml::xml_node<>* node_orientation = doc.allocate_node(rapidxml::node_element, "model_orientation");
00076     std::string orientation = object_params.at(4) + ", " + object_params.at(5) + ", " + object_params.at(6);
00077     node_orientation->value(orientation.c_str());
00078     root->append_node(node_orientation);
00079 
00080     rapidxml::xml_node<>* node_diameter = doc.allocate_node(rapidxml::node_element, "diameter");
00081     node_diameter->value(object_params.at(7).c_str());
00082     root->append_node(node_diameter);
00083 
00084     rapidxml::xml_node<>* node_score3D = doc.allocate_node(rapidxml::node_element, "score3D");
00085     node_score3D->value(object_params.at(8).c_str());
00086     root->append_node(node_score3D);
00087 
00088     rapidxml::xml_node<>* node_desc_models = doc.allocate_node(rapidxml::node_element, "descriptor_models");
00089 
00090     for (unsigned int i = 0; i < views.size(); i++) {
00091 
00092         rapidxml::xml_node<>* node_desc_model = doc.allocate_node(rapidxml::node_element, "descriptor_model");
00093 
00094         rapidxml::xml_node<>* node_desc_model_name = doc.allocate_node(rapidxml::node_element, "name");
00095         std::string desc_model_name = object_params.at(0) + "_view_" + boost::lexical_cast<std::string>(i + 1) + ".dsm";
00096 
00097         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";
00098 
00099         node_desc_model_name->value(doc.allocate_string(desc_model_name.c_str()));
00100         node_desc_model->append_node(node_desc_model_name);
00101 
00102         std::string view_image_name = object_params.at(0) + "_view_" + boost::lexical_cast<std::string>(i + 1) + ".png";
00103         try {
00104             //create desc model
00105             HalconCpp::HImage img = views.at(i).getImage();
00106             if (!(views.at(i).getUseColor())) {
00107                 img = img.Rgb1ToGray();
00108             }
00109             img.WriteImage("png", 0, (output_path.string() + view_image_name).c_str());
00110             HalconCpp::HTuple descparamname("depth");
00111             descparamname.Append("number_ferns");
00112             descparamname.Append("patch_size");
00113             descparamname.Append("max_scale");
00114             descparamname.Append("min_scale");
00115             HalconCpp::HTuple descparamvalue(views.at(i).getDepth());
00116             descparamvalue.Append(views.at(i).getNumberFerns());
00117             descparamvalue.Append(views.at(i).getPatchSize());
00118             descparamvalue.Append(views.at(i).getMaxScale());
00119             descparamvalue.Append(views.at(i).getMinScale());
00120             img.CreateUncalibDescriptorModel("harris_binomial", HalconCpp::HTuple(), HalconCpp::HTuple(), descparamname, descparamvalue, 42).WriteDescriptorModel((output_path.string() + desc_model_name).c_str());
00121             logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Descriptor model creation successful (" << desc_model_name << ").\n";
00122         } catch(HalconCpp::HException exc) {
00123             logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Could not create descriptor model (" << desc_model_name << "), Error msg: " << exc.ErrorText() << ".\n";
00124             success = false;
00125             continue;
00126         }
00127 
00128 
00129 
00130         rapidxml::xml_node<>* node_desc_model_orientation = doc.allocate_node(rapidxml::node_element, "view_orientation");
00131         std::string view_or_0 = boost::lexical_cast<std::string>(views.at(i).getOrientation()[0]);
00132         std::string view_or_1 = boost::lexical_cast<std::string>(views.at(i).getOrientation()[1]);
00133         std::string view_or_2 = boost::lexical_cast<std::string>(views.at(i).getOrientation()[2]);
00134         std::replace(view_or_0.begin(), view_or_0.end(), ',', '.');
00135         std::replace(view_or_1.begin(), view_or_1.end(), ',', '.');
00136         std::replace(view_or_2.begin(), view_or_2.end(), ',', '.');
00137         std::string desc_model_orientation = view_or_0 + ", " + view_or_1 + ", " + view_or_2;
00138 
00139         node_desc_model_orientation->value(doc.allocate_string(desc_model_orientation.c_str()));
00140         node_desc_model->append_node(node_desc_model_orientation);
00141 
00142         rapidxml::xml_node<>* node_desc_model_score2D = doc.allocate_node(rapidxml::node_element, "score2D");
00143         std::string desc_model_score2D = boost::lexical_cast<std::string>(views.at(i).getScore2D());
00144         std::replace(desc_model_score2D.begin(), desc_model_score2D.end(), ',', '.');
00145         node_desc_model_score2D->value(doc.allocate_string(desc_model_score2D.c_str()));
00146         node_desc_model->append_node(node_desc_model_score2D);
00147 
00148         rapidxml::xml_node<>* node_desc_model_use_color = doc.allocate_node(rapidxml::node_element, "use_color");
00149         std::string desc_model_use_color = boost::lexical_cast<std::string>(views.at(i).getUseColor());
00150         node_desc_model_use_color->value(doc.allocate_string(desc_model_use_color.c_str()));
00151         node_desc_model->append_node(node_desc_model_use_color);
00152 
00153         rapidxml::xml_node<>* node_desc_model_vertical_offset = doc.allocate_node(rapidxml::node_element, "vertical_texture_offset");
00154         std::string desc_model_vertical_offset = boost::lexical_cast<std::string>(views.at(i).getVerticalOffset());
00155         node_desc_model_vertical_offset->value(doc.allocate_string(desc_model_vertical_offset.c_str()));
00156         node_desc_model->append_node(node_desc_model_vertical_offset);
00157 
00158         rapidxml::xml_node<>* node_desc_model_horizontal_offset = doc.allocate_node(rapidxml::node_element, "horizontal_texture_offset");
00159         std::string desc_model_horizontal_offset = boost::lexical_cast<std::string>(views.at(i).getHorizontalOffset());
00160         node_desc_model_horizontal_offset->value(doc.allocate_string(desc_model_horizontal_offset.c_str()));
00161         node_desc_model->append_node(node_desc_model_horizontal_offset);
00162 
00163         rapidxml::xml_node<>* node_desc_model_invertible = doc.allocate_node(rapidxml::node_element, "invertible");
00164         std::string desc_model_invertible = boost::lexical_cast<std::string>(views.at(i).getIsInvertible());
00165         node_desc_model_invertible->value(doc.allocate_string(desc_model_invertible.c_str()));
00166         node_desc_model->append_node(node_desc_model_invertible);
00167 
00168         rapidxml::xml_node<>* node_desc_model_bounding_box = doc.allocate_node(rapidxml::node_element, "bounding_box");
00169         for (unsigned int j = 0; j < views.at(i).getBoxCorners().size(); j++) {
00170             rapidxml::xml_node<>* node_desc_model_bounding_box_corner = doc.allocate_node(rapidxml::node_element, "corner_point");
00171             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()));
00172             node_desc_model_bounding_box_corner->value(doc.allocate_string(point_vector.c_str()));
00173             node_desc_model_bounding_box->append_node(node_desc_model_bounding_box_corner);
00174         }
00175 
00176         node_desc_model->append_node(node_desc_model_bounding_box);
00177 
00178 
00179         if (views.at(i).getRotationType() != ROTATIONTYPE_NO_ROTATION) {
00180             rapidxml::xml_node<>* node_desc_model_axes = doc.allocate_node(rapidxml::node_element, "rotation_axes");
00181 
00182             rapidxml::xml_node<>* node_desc_model_axis_1 = doc.allocate_node(rapidxml::node_element, "axis_1");
00183             std::string axis_1_x =boost::lexical_cast<std::string>(views.at(i).getAxis1()[0]);
00184             std::string axis_1_y =boost::lexical_cast<std::string>(views.at(i).getAxis1()[1]);
00185             std::string axis_1_z =boost::lexical_cast<std::string>(views.at(i).getAxis1()[2]);
00186             std::replace(axis_1_x.begin(), axis_1_x.end(), ',', '.');
00187             std::replace(axis_1_y.begin(), axis_1_y.end(), ',', '.');
00188             std::replace(axis_1_z.begin(), axis_1_z.end(), ',', '.');
00189 
00190             std::string desc_model_axis_1 = axis_1_x + ", " + axis_1_y + ", " + axis_1_z;
00191             node_desc_model_axis_1->value(doc.allocate_string(desc_model_axis_1.c_str()));
00192             std::string desc_model_axis_1_angle = boost::lexical_cast<std::string>(views.at(i).getAxis1Angle());
00193             std::replace(desc_model_axis_1_angle.begin(), desc_model_axis_1_angle.end(), ',', '.');
00194 
00195             rapidxml::xml_attribute<> *axis_1_angle_attr = doc.allocate_attribute("angle", doc.allocate_string(desc_model_axis_1_angle.c_str()));
00196             node_desc_model_axis_1->append_attribute(axis_1_angle_attr);
00197             node_desc_model_axes->append_node(node_desc_model_axis_1);
00198 
00199             if (views.at(i).getRotationType() == ROTATIONTYPE_SPHERE) {
00200                 rapidxml::xml_node<>* node_desc_model_axis_2 = doc.allocate_node(rapidxml::node_element, "axis_2");
00201                 std::string axis_2_x =boost::lexical_cast<std::string>(views.at(i).getAxis2()[0]);
00202                 std::string axis_2_y =boost::lexical_cast<std::string>(views.at(i).getAxis2()[1]);
00203                 std::string axis_2_z =boost::lexical_cast<std::string>(views.at(i).getAxis2()[2]);
00204                 std::replace(axis_2_x.begin(), axis_2_x.end(), ',', '.');
00205                 std::replace(axis_2_y.begin(), axis_2_y.end(), ',', '.');
00206                 std::replace(axis_2_z.begin(), axis_2_z.end(), ',', '.');
00207                 std::string desc_model_axis_2 = axis_2_x + ", " + axis_2_y + ", " + axis_2_z;
00208                 node_desc_model_axis_2->value(doc.allocate_string(desc_model_axis_2.c_str()));
00209                 std::string desc_model_axis_2_angle = boost::lexical_cast<std::string>(views.at(i).getAxis2Angle());
00210                 std::replace(desc_model_axis_2_angle.begin(), desc_model_axis_2_angle.end(), ',', '.');
00211                 rapidxml::xml_attribute<> *axis_2_angle_attr = doc.allocate_attribute("angle", doc.allocate_string(desc_model_axis_2_angle.c_str()));
00212                 node_desc_model_axis_2->append_attribute(axis_2_angle_attr);
00213                 node_desc_model_axes->append_node(node_desc_model_axis_2);
00214             }
00215 
00216             node_desc_model->append_node(node_desc_model_axes);
00217         }
00218         node_desc_models->append_node(node_desc_model);
00219 
00220         progress_bar->SetValue(progress_bar->GetValue() + 1);
00221     }
00222     root->append_node(node_desc_models);
00223 
00224     std::string filename = object_params.at(0) + ".xml";
00225     filename = output_path.string() + filename;
00226     std::ofstream file_stored(filename.c_str());
00227     file_stored << doc;
00228     file_stored.close();
00229     doc.clear();
00230 
00231     logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "XML-file successfully created.\n";
00232 
00233     progress_bar->SetValue(progress_bar->GetValue() + 1);
00234 
00235     logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Creating surface model.\n";
00236     try {
00237         std::string object_model_path = input_path.string() + object_params.at(1);
00238         HalconCpp::HObjectModel3D model;
00239         model.ReadObjectModel3d(object_model_path.c_str(), "mm", HalconCpp::HTuple(), HalconCpp::HTuple());
00240         HalconCpp::HSurfaceModel surface_mdl = model.CreateSurfaceModel(0.035, HalconCpp::HTuple(), HalconCpp::HTuple());
00241         surface_mdl.WriteSurfaceModel((output_path.string() + object_params.at(0) + "_surfaceMdl.sfm").c_str());
00242         logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Surface model successfully created.\n";
00243     } catch (HalconCpp::HException exc) {
00244         logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Surface model could not be created, error msg: " << exc.ErrorText() << ".\n";
00245         success = false;
00246     }
00247     progress_bar->SetValue(progress_bar->GetValue() + 1);
00248 
00249     logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Copying mesh file.\n";
00250     std::string mesh_path = input_path.string() + object_params.at(2);
00251     std::string mesh_destination_path = output_path.string() + object_params.at(2);
00252     try {
00253         boost::filesystem::copy_file(mesh_path, mesh_destination_path, boost::filesystem::copy_option::overwrite_if_exists);
00254         logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Mesh file successfully copied.\n";
00255     } catch (boost::filesystem::filesystem_error err) {
00256         logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Could not copy mesh file.\n";
00257         success = false;
00258     }
00259     progress_bar->SetValue(progress_bar->GetValue() + 1);
00260 
00261     logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Copying texture-file of mesh.\n";
00262     try {
00263         rapidxml::file<> xmlFile(mesh_path.c_str());
00264         rapidxml::xml_document<> mesh_doc;
00265         mesh_doc.parse<0>(xmlFile.data());
00266         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")) {
00267             std::string texture_name = mesh_doc.first_node()->first_node("library_images")->first_node("image")->first_node("init_from")->value();
00268             std::string texture_path = input_path.string() + texture_name;
00269             std::string texture_destination_path = output_path.string() + texture_name;
00270             boost::filesystem::copy_file(texture_path, texture_destination_path, boost::filesystem::copy_option::overwrite_if_exists);
00271             logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Texture file successfully copied.\n";
00272         } else {
00273             logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Could not copy mesh file.\n";
00274             success = false;
00275         }
00276     } catch(boost::filesystem::filesystem_error err) {
00277         logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Could not copy mesh file.\n";
00278         success = false;
00279     } catch (std::runtime_error err) {
00280         logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Error: Could not copy mesh file.\n";
00281         success = false;
00282     }
00283     progress_bar->SetValue(progress_bar->GetValue() + 1);
00284 
00285 
00286 
00287     if (progress_bar->GetValue() < progress_bar->GetRange()) {
00288         progress_bar->SetValue(progress_bar->GetRange());
00289     }
00290     logFile << "[" << boost::lexical_cast<std::string>(ros::Time::now().toSec()) << "] " << "Output files creation done.\n";
00291     logFile.close();
00292     button_done->Enable();
00293 
00294 }
00295 
00296 CreateOutputFilesDialog::CreateOutputFilesDialog(DescModelsDialog* parent_dialog)
00297     : Create_Output_Files_Dialog_Base(parent_dialog),
00298       views(parent_dialog->getViews()),
00299       object_params(parent_dialog->getObjectParameters()),
00300       success(true)
00301 {
00302     button_done->Enable(false);
00303     progress_bar->SetRange(4 + views.size());
00304 
00305     boost::thread create_files_thread(boost::bind(&CreateOutputFilesDialog::createOutputFiles, this));
00306 }
00307 
00308 void CreateOutputFilesDialog::onButtonDoneClicked(wxCommandEvent &event)
00309 {
00310     if (success) {
00311         EndModal(wxID_OK);
00312     } else {
00313         EndModal(wxID_CANCEL);
00314     }
00315     Destroy();
00316 }
00317 
00318 void CreateOutputFilesDialog::onDialogClose(wxCloseEvent &event)
00319 {
00320 
00321 }


asr_descriptor_surface_based_recognition
Author(s): Allgeyer Tobias, Hutmacher Robin, Meißner Pascal
autogenerated on Thu Jun 6 2019 17:57:29