View_Creator_Dialog.cpp
Go to the documentation of this file.
00001 
00021 #include "descriptor_surface_based_trainer/View_Creator_Dialog.h"
00022 #include "descriptor_surface_based_trainer/Create_Test_Model_Dialog.h"
00023 #include <wx/sizer.h>
00024 #include <asr_halcon_bridge/halcon_image.h>
00025 #include <boost/regex.hpp>
00026 #include <ros/package.h>
00027 #include "descriptor_surface_based_trainer/Utils.h"
00028 #include <boost/thread.hpp>
00029 
00030 
00031 
00032 void ViewCreatorDialog::enableGuiElements(bool enable)
00033 {
00034     edit_upper_left_row->Enable(enable);
00035     edit_upper_left_column->Enable(enable);
00036     edit_lower_right_row->Enable(enable);
00037     edit_lower_right_column->Enable(enable);
00038     slider_upper_left_row->Enable(enable);
00039     slider_upper_left_column->Enable(enable);
00040     slider_lower_right_row->Enable(enable);
00041     slider_lower_right_column->Enable(enable);
00042     edit_orientation_x->Enable(enable);
00043     edit_orientation_y->Enable(enable);
00044     edit_orientation_z->Enable(enable);
00045     edit_score_2D->Enable(enable);
00046     edit_vertical_offset->Enable(enable);
00047     edit_horizontal_offset->Enable(enable);
00048     edit_axis_1_x->Enable(enable);
00049     edit_axis_1_y->Enable(enable);
00050     edit_axis_1_z->Enable(enable);
00051     edit_axis_1_angle->Enable(enable);
00052     edit_axis_2_x->Enable(enable);
00053     edit_axis_2_y->Enable(enable);
00054     edit_axis_2_z->Enable(enable);
00055     edit_axis_2_angle->Enable(enable);
00056     edit_depth->Enable(enable);
00057     edit_fern_number->Enable(enable);
00058     edit_patch_size->Enable(enable);
00059     edit_min_scale->Enable(enable);
00060     edit_max_scale->Enable(enable);
00061     check_invertable->Enable(enable);
00062     check_use_color->Enable(enable);
00063 }
00064 
00065 void ViewCreatorDialog::enableGuiElementsTest(bool enable)
00066 {
00067 
00068     enableGuiElements(enable);
00069     choice_image_source->Enable(enable);
00070     choice_image->Enable(enable);
00071     choice_test_image->Enable(enable);
00072     choice_test_image_source->Enable(enable);
00073     if ((choice_image_source->GetSelection() == 2) && (choice_image->GetSelection() > 0)) {
00074         check_fix_current_image->Enable(enable);
00075     }
00076     button_save->Enable(enable);
00077     button_cancel->Enable(enable);
00078 
00079 }
00080 
00081 
00082 void ViewCreatorDialog::updateImageOnCrop() {
00083     if ((check_fix_current_image->IsChecked()) && (fixed_image_available)) {
00084 
00085         int row1 = boost::lexical_cast<int>(trim(std::string(edit_upper_left_row->GetValue().mb_str())));
00086         int column1 = boost::lexical_cast<int>(trim(std::string(edit_upper_left_column->GetValue().mb_str())));
00087         int row2 = boost::lexical_cast<int>(trim(std::string(edit_lower_right_row->GetValue().mb_str())));
00088         int column2 = boost::lexical_cast<int>(trim(std::string(edit_lower_right_column->GetValue().mb_str())));
00089 
00090         HalconCpp::HRegion region;
00091         region.GenRectangle1(row1, column1, row2, column2);
00092         HalconCpp::HImage croppedImage = fixedImage.ReduceDomain(region);
00093         croppedImage = croppedImage.ChangeFormat(croppedImage.Width(), croppedImage.Height());
00094 
00095         image_model->setImage(createBitmap(croppedImage, 480, 360));
00096         image_model->paintNow();
00097 
00098     }
00099 }
00100 
00101 void ViewCreatorDialog::paint_test_image(HalconCpp::HImage img)
00102 {
00103     img = img.ZoomImageSize(480, 360, "bilinear");
00104     image_test->setImage(createBitmap(img, 480, 360));
00105     image_test->paintNow();
00106 
00107 }
00108 
00109 
00110 
00111 ViewCreatorDialog::ViewCreatorDialog(wxWindow *parent, ViewParamsWrapper *params)
00112     : ViewCreatorDialogBase(parent), params(params), fixed_image_available(false),
00113       desc_model_available(false), test_running(false), frame_counter(0),
00114       score_sum(0), feature_sum(0), time_sum(0), update_timer(0)
00115 {
00116 
00117     if (params->getRotationType() == ROTATIONTYPE_NO_ROTATION || params->getRotationType() == ROTATIONTYPE_CYLINDER) {
00118        label_axis_2->Show(false);
00119         label_axis_2_x->Show(false);
00120         edit_axis_2_x->Show(false);
00121         label_axis_2_y->Show(false);
00122         edit_axis_2_y->Show(false);
00123         label_axis_2_z->Show(false);
00124         edit_axis_2_z->Show(false);
00125         label_axis_2_angle->Show(false);
00126         edit_axis_2_angle->Show(false);
00127 
00128         if (params->getRotationType() == ROTATIONTYPE_NO_ROTATION) {
00129             label_axis_1->Show(false);
00130             label_axis_1_x->Show(false);
00131             edit_axis_1_x->Show(false);
00132             label_axis_1_y->Show(false);
00133             edit_axis_1_y->Show(false);
00134             label_axis_1_z->Show(false);
00135             edit_axis_1_z->Show(false);
00136             label_axis_1_angle->Show(false);
00137             edit_axis_1_angle->Show(false);
00138         }
00139     }
00140 
00141 
00142     update_timer = new wxTimer(this);
00143     update_timer->Start(200);
00144     Connect(update_timer->GetId(), wxEVT_TIMER, wxTimerEventHandler(ViewCreatorDialog::onUpdate), NULL, this);
00145 
00146     image_test->setImage(new wxBitmap(wxImage(480, 360)));
00147     image_test->paintNow();
00148 
00149 
00150 
00151     if (params->getIsValid()) {
00152         choice_image_source->AppendString(wxT("edit image"));
00153         choice_image_source->SetSelection(3);
00154         wxCommandEvent evt;
00155         onChoiceImageSource(evt);
00156 
00157     } else {
00158         image_model->setImage(new wxBitmap(wxImage(480, 360)));
00159         image_model->paintNow();
00160 
00161         choice_image->Clear();
00162         choice_image->Insert(wxString("<No selection>",  wxConvUTF8), 0);
00163         choice_image->SetSelection(0);
00164 
00165         choice_test_image->Clear();
00166         choice_test_image->Insert(wxString("<No selection>",  wxConvUTF8), 0);
00167         choice_test_image->SetSelection(0);
00168 
00169         edit_upper_left_row->SetValue(wxT("0"));
00170         edit_upper_left_column->SetValue(wxT("0"));
00171         edit_lower_right_row->SetValue(wxT("359"));
00172         edit_lower_right_column->SetValue(wxT("479"));
00173         slider_lower_right_row->SetMax(359);
00174         slider_lower_right_row->SetValue(359);
00175         slider_lower_right_column->SetMax(479);
00176         slider_lower_right_column->SetValue(479);
00177         edit_score_2D->SetValue(wxT("0.2"));
00178         edit_vertical_offset->SetValue(wxT("0"));
00179         edit_horizontal_offset->SetValue(wxT("0"));
00180         edit_axis_1_angle->SetValue(wxT("1.0"));
00181         edit_axis_2_angle->SetValue(wxT("1.0"));
00182         edit_depth->SetValue(wxT("8"));
00183         edit_fern_number->SetValue(wxT("50"));
00184         edit_patch_size->SetValue(wxT("17"));
00185         edit_min_scale->SetValue(wxT("0.6"));
00186         edit_max_scale->SetValue(wxT("1.3"));
00187 
00188 
00189         enableGuiElements(false);
00190 
00191         check_fix_current_image->Enable(false);
00192 
00193     }
00194 
00195     label_model_points_value->SetLabel(wxT("0"));
00196     label_search_points_value->SetLabel(wxT("0"));
00197     label_matched_points_value->SetLabel(wxT("0"));
00198     label_average_matched_points_value->SetLabel(wxT("0"));
00199     label_time_value->SetLabel(wxT("0.0"));
00200     label_average_time_value->SetLabel(wxT("0.0"));
00201     button_end_test->Enable(false);
00202 
00203 
00204 }
00205 
00206 void ViewCreatorDialog::onModelCameraImage(const sensor_msgs::Image::ConstPtr& msg) {
00207     if (!check_fix_current_image->IsChecked()) {
00208         image_model->setImage(createBitmap(msg, 480, 360));
00209         image_model->paintNow();
00210     } else if (!fixed_image_available){
00211         if ((msg->encoding == "bgr8") || (msg->encoding == "rgb8") || (msg->encoding == "mono8")) {
00212             image_model->setImage(createBitmap(msg, 480, 360));
00213             image_model->paintNow();
00214             fixedImage = *halcon_bridge::toHalconCopy(*msg)->image;
00215             fixed_image_available = true;
00216 
00217             slider_upper_left_column->SetValue(0);
00218             slider_upper_left_column->SetMax((int)fixedImage.Width() - 1);
00219             edit_upper_left_column->SetValue(wxString::Format(wxT("%i"), 0));
00220 
00221             slider_upper_left_row->SetMax((int)fixedImage.Height() - 1);
00222             slider_upper_left_row->SetValue(0);
00223             edit_upper_left_row->SetValue(wxString::Format(wxT("%i"), 0));
00224 
00225             slider_lower_right_column->SetMax((int)fixedImage.Width() - 1);
00226             slider_lower_right_column->SetValue((int)fixedImage.Width() - 1);
00227             edit_lower_right_column->SetValue(wxString::Format(wxT("%i"),(int)fixedImage.Width() - 1));
00228 
00229             slider_lower_right_row->SetMax((int)fixedImage.Height() - 1);
00230             slider_lower_right_row->SetValue((int)fixedImage.Height() - 1);
00231             edit_lower_right_row->SetValue(wxString::Format(wxT("%i"),(int)fixedImage.Height() - 1));
00232 
00233             enableGuiElements(true);
00234         }
00235     }
00236 }
00237 
00238 
00239 
00240 void ViewCreatorDialog::onTestCameraImage(const sensor_msgs::Image::ConstPtr& msg, bool use_file) {
00241     if (test_running ) {
00242         HalconCpp::HImage img;
00243         std::string enc = "rgb8";
00244         if (use_file) {
00245             boost::filesystem::path input_path(ros::package::getPath("asr_descriptor_surface_based_recognition") + INPUT_FOLDER + "/");
00246             std::string filename_str = input_path.string() + std::string(choice_test_image->GetStringSelection().mb_str());
00247             img = HalconCpp::HImage(filename_str.c_str());
00248         } else {
00249             enc = msg->encoding;
00250             img = *halcon_bridge::toHalconCopy(msg)->image;
00251         }
00252         frame_counter++;
00253         HalconCpp::HTuple sc, search_all_row, search_all_column, search_row, search_column, model_row, model_column;
00254         HalconCpp::HTuple color(255);
00255         if (!(check_use_color->IsChecked())) {
00256             img = img.Rgb1ToGray();
00257             enc = "mono8";
00258         } else {
00259             color.Append(255);
00260             color.Append(0);
00261         }
00262 
00263         try {
00264             ros::Time start_time = ros::Time::now();
00265             double set_score = boost::lexical_cast<double>(trim(std::string(edit_score_2D->GetValue().mb_str())));
00266             if ((set_score <= 0) || (set_score >= 1)) {
00267                 set_score = 0.0;
00268             }
00269             img.FindUncalibDescriptorModel(desc_model, HalconCpp::HTuple(), HalconCpp::HTuple(), HalconCpp::HTuple(), HalconCpp::HTuple(), set_score, 1, "inlier_ratio", &sc);
00270             ros::Duration search_duration = ros::Time::now() - start_time;
00271             time_sum += search_duration.toSec();
00272             label_time_value->SetLabel(wxString::Format(wxT("%f"), search_duration.toSec()));
00273             label_average_time_value->SetLabel(wxString::Format(wxT("%f"), time_sum / frame_counter));
00274             desc_model.GetDescriptorModelPoints("search", "all", &search_all_row, &search_all_column);
00275 
00276             label_search_points_value->SetLabel(wxString::Format(wxT("%i"), search_all_row.Length()));
00277             desc_model.GetDescriptorModelPoints("search", 0, &search_row, &search_column);
00278             label_matched_points_value->SetLabel(wxString::Format(wxT("%i"), search_row.Length()));
00279             if (search_row.Length() > 0) {
00280                 HalconCpp::HRegion points;
00281                 points.GenRegionPoints(search_row, search_column);
00282                 HalconCpp::HString type = "fill";
00283                 img = points.PaintRegion(img, color, type);
00284 
00285                 int vertical_offset = boost::lexical_cast<int>(trim(std::string(edit_vertical_offset->GetValue().mb_str())));
00286                 int horizontal_offset = boost::lexical_cast<int>(trim(std::string(edit_horizontal_offset->GetValue().mb_str())));
00287                 HalconCpp::HTuple matrix_tuple = desc_model.GetDescriptorModelResults(0, "homography");
00288                 HalconCpp::HHomMat2D matrix;
00289                 matrix.SetFromTuple(matrix_tuple);
00290 
00291                 double trans_x, trans_y, trans_w;
00292                 trans_x = matrix.ProjectiveTransPoint2d(vertical_offset, horizontal_offset, 1,  &trans_y, &trans_w);
00293 
00294                 int tex_point_row = (int) (trans_x / trans_w);
00295                 int tex_point_column = (int) (trans_y / trans_w);
00296 
00297                 HalconCpp::HXLDCont tex_point;
00298                 tex_point.GenCircleContourXld(tex_point_row, tex_point_column, 10, 0, 6.28318, "positive", 1);
00299                 img = tex_point.PaintXld(img, color);
00300 
00301 
00302             }
00303             feature_sum += search_row.Length();
00304             label_average_matched_points_value->SetLabel(wxString::Format(wxT("%i"), (int)(feature_sum / frame_counter)));
00305 
00306 
00307 
00308         }catch (HalconCpp::HException exc) {
00309             label_matched_points_value->SetLabel(wxT("0"));
00310         }
00311         double score = 0;
00312         if (sc.Length() > 0) {
00313             score = sc[0];
00314         }
00315 
00316         score_sum += score;
00317         label_score_value->SetLabel(wxString::Format(wxT("%f"), score));
00318         label_frame_number_value->SetLabel(wxString::Format(wxT("%i"), frame_counter));
00319         label_average_score_value->SetLabel(wxString::Format(wxT("%f"), score_sum / frame_counter));
00320 
00321 
00322         desc_model.GetDescriptorModelPoints("model", "all", &model_row, &model_column);
00323         label_model_points_value->SetLabel(wxString::Format(wxT("%i"), model_row.Length()));
00324 
00325 
00326         paint_thread = boost::thread(boost::bind(&ViewCreatorDialog::paint_test_image, this, img));
00327 
00328         paint_thread.timed_join(boost::posix_time::millisec(100));
00329 
00330 
00331 
00332 
00333     } else {
00334         paint_thread.join();
00335         image_test->setImage(createBitmap(msg, 480, 360));
00336         image_test->paintNow();
00337     }
00338 
00339 }
00340 
00341 
00342 void ViewCreatorDialog::onUpdate(wxTimerEvent &evt)
00343 {
00344     ros::spinOnce();
00345     if (!ros::ok())
00346     {
00347         update_timer->Stop();
00348         EndModal(wxID_CANCEL);
00349         Destroy();
00350     }
00351     if ((choice_test_image_source->GetSelection() == 1) && (choice_test_image->GetSelection() > 0) && (test_running) && (desc_model_available)) {
00352         if (update_counter == 0) {
00353             paint_thread.join();
00354             sensor_msgs::ImageConstPtr msg;
00355             onTestCameraImage(msg, true);
00356         }
00357     }
00358 
00359     update_counter = ((update_counter + 1) % 3);
00360 }
00361 
00362 
00363 
00364 void ViewCreatorDialog::OnDialogClose(wxCloseEvent &event)
00365 {
00366     wxMessageDialog *dial = new wxMessageDialog(this,
00367           wxT("Are you sure you want to cancel?"), wxT("Cancel"),
00368           wxYES_NO | wxNO_DEFAULT | wxICON_QUESTION);
00369       if (dial->ShowModal() == wxID_YES) {
00370           update_timer->Stop();
00371           image_model_sub.shutdown();
00372           image_test_sub.shutdown();
00373           EndModal(wxID_CANCEL);
00374           Destroy();
00375       }
00376 }
00377 
00378 void ViewCreatorDialog::onChoiceImageSource( wxCommandEvent& event )
00379 {
00380     image_model_sub.shutdown();
00381     choice_image->Clear();
00382     if (choice_image_source->GetSelection() != 3) {
00383         wxBitmap* empty = new wxBitmap(wxImage(480, 360));
00384         image_model->setImage(empty);
00385         image_model->paintNow();
00386         choice_image->Insert(wxString("<No selection>",  wxConvUTF8), 0);
00387         choice_image->SetSelection(0);
00388 
00389         check_fix_current_image->Enable(false);
00390         check_fix_current_image->SetValue(false);
00391         enableGuiElements(false);
00392         fixed_image_available = false;
00393     }
00394 
00395     desc_model_available = false;
00396     label_model_available_value->SetLabel(wxT("No"));
00397 
00398     switch (choice_image_source->GetSelection()) {
00399         case 1:
00400             {
00401                 std::vector<boost::filesystem::path> files;
00402                 boost::filesystem::path input_path(ros::package::getPath("asr_descriptor_surface_based_recognition") + INPUT_FOLDER + "/");
00403                 get_all_files_with_ext(input_path, ".png", files);
00404                 get_all_files_with_ext(input_path, ".jpg", files);
00405                 std::sort(files.begin(), files.end());
00406                 for (unsigned int i = 0; i < files.size(); i++) {
00407                     choice_image->AppendString(wxString(files[i].string().c_str(), wxConvUTF8));
00408                 }
00409 
00410                 break;
00411             }
00412         case 2:
00413             {
00414                 std::vector<std::string> image_topics;
00415                 ros::master::V_TopicInfo master_topics;
00416                 ros::master::getTopics(master_topics);
00417 
00418                 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
00419                     const ros::master::TopicInfo& info = *it;
00420                     if (info.datatype == "sensor_msgs/Image") {
00421                         image_topics.push_back(info.name);
00422                     }
00423                 }
00424                 std::sort(image_topics.begin(), image_topics.end());
00425                 for (unsigned int i = 0; i < image_topics.size(); i++) {
00426                     choice_image->Insert(wxString(image_topics.at(i).c_str(), wxConvUTF8),i + 1);
00427                 }
00428                 break;
00429             }
00430         case 3:
00431             {
00432                 choice_image->AppendString(wxT("editable image"));
00433                 choice_image->SetSelection(0);
00434                 wxCommandEvent evt;
00435                 onChoiceImage(evt);
00436             }
00437     }
00438 }
00439 
00440 void ViewCreatorDialog::onChoiceImage( wxCommandEvent& event )
00441 {
00442     image_model_sub.shutdown();
00443     desc_model_available = false;
00444     label_model_available_value->SetLabel(wxT("No"));
00445 
00446     //case: edit image
00447     if (choice_image_source->GetSelection() == 3) {
00448         enableGuiElements(true);
00449         check_fix_current_image->SetValue(true);
00450         check_fix_current_image->Enable(false);
00451         fixed_image_available = true;
00452 
00453 
00454         fixedImage = params->getOriginalImage();
00455 
00456         slider_upper_left_column->SetMax((int)fixedImage.Width() - 1);
00457         slider_upper_left_column->SetValue(params->getColumn1());
00458         edit_upper_left_column->SetValue(wxString::Format(wxT("%i"), params->getColumn1()));
00459 
00460         slider_upper_left_row->SetMax((int)fixedImage.Height() - 1);
00461         slider_upper_left_row->SetValue(params->getRow1());
00462         edit_upper_left_row->SetValue(wxString::Format(wxT("%i"), params->getRow1()));
00463 
00464         slider_lower_right_column->SetMax((int)fixedImage.Width() - 1);
00465         slider_lower_right_column->SetValue(params->getColumn2());
00466         edit_lower_right_column->SetValue(wxString::Format(wxT("%i"),params->getColumn2()));
00467 
00468         slider_lower_right_row->SetMax((int)fixedImage.Height() - 1);
00469         slider_lower_right_row->SetValue(params->getRow2());
00470         edit_lower_right_row->SetValue(wxString::Format(wxT("%i"),params->getRow2()));
00471 
00472         updateImageOnCrop();
00473 
00474         edit_orientation_x->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getOrientation()[0])));
00475         edit_orientation_y->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getOrientation()[1])));
00476         edit_orientation_z->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getOrientation()[2])));
00477 
00478         if (params->getRotationType() != ROTATIONTYPE_NO_ROTATION) {
00479             edit_axis_1_x->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getAxis1()[0])));
00480             edit_axis_1_y->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getAxis1()[1])));
00481             edit_axis_1_z->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getAxis1()[2])));
00482             edit_axis_1_angle->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getAxis1Angle())));
00483             if (params->getRotationType() == ROTATIONTYPE_SPHERE) {
00484                 edit_axis_2_x->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getAxis2()[0])));
00485                 edit_axis_2_y->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getAxis2()[1])));
00486                 edit_axis_2_z->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getAxis2()[2])));
00487                 edit_axis_2_angle->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getAxis2Angle())));
00488             }
00489         }
00490 
00491         edit_score_2D->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getScore2D())));
00492         edit_vertical_offset->SetValue(wxString::Format(wxT("%i"), params->getVerticalOffset()));
00493         edit_horizontal_offset->SetValue(wxString::Format(wxT("%i"), params->getHorizontalOffset()));
00494 
00495         edit_depth->SetValue(wxString::Format(wxT("%i"), params->getDepth()));
00496         edit_fern_number->SetValue(wxString::Format(wxT("%i"), params->getNumberFerns()));
00497         edit_patch_size->SetValue(wxString::Format(wxT("%i"), params->getPatchSize()));
00498         edit_min_scale->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getMinScale())));
00499         edit_max_scale->SetValue(trimDoubleString(wxString::Format(wxT("%f"), params->getMaxScale())));
00500 
00501         if (params->getIsInvertible()) {
00502             check_invertable->SetValue(true);
00503         }
00504         if (params->getUseColor()) {
00505             check_use_color->SetValue(true);
00506         }
00507 
00508     //case: no editing
00509     } else {
00510         enableGuiElements(false);
00511         check_fix_current_image->SetValue(false);
00512         fixed_image_available = false;
00513         if (choice_image->GetSelection() > 0) {
00514             if (choice_image_source->GetSelection() == 2) {
00515                 check_fix_current_image->Enable(true);
00516                 std::string str = std::string(choice_image->GetStringSelection().mb_str());
00517                 image_model_sub = nh.subscribe<sensor_msgs::Image>(str, 1, &ViewCreatorDialog::onModelCameraImage, this);
00518             } else if (choice_image_source->GetSelection() == 1) {
00519                 boost::filesystem::path input_path(ros::package::getPath("asr_descriptor_surface_based_recognition") + INPUT_FOLDER + "/");
00520                 wxString filename = wxString(input_path.string().c_str(), wxConvUTF8) + choice_image->GetStringSelection();
00521                 wxImage image(filename);
00522                 image = image.Scale(480, 360);
00523                 image_model->setImage(new wxBitmap(image));
00524                 image_model->paintNow();
00525 
00526                 check_fix_current_image->SetValue(true);
00527 
00528                 std::string filename_str = input_path.string() + std::string(choice_image->GetStringSelection().mb_str());
00529                 fixedImage = HalconCpp::HImage(filename_str.c_str());
00530 
00531                 fixed_image_available = true;
00532 
00533                 slider_upper_left_column->SetValue(0);
00534                 slider_upper_left_column->SetMax((int)fixedImage.Width() - 1);
00535                 edit_upper_left_column->SetValue(wxString::Format(wxT("%i"), 0));
00536 
00537                 slider_upper_left_row->SetMax((int)fixedImage.Height() - 1);
00538                 slider_upper_left_row->SetValue(0);
00539                 edit_upper_left_row->SetValue(wxString::Format(wxT("%i"), 0));
00540 
00541                 slider_lower_right_column->SetMax((int)fixedImage.Width() - 1);
00542                 slider_lower_right_column->SetValue((int)fixedImage.Width() - 1);
00543                 edit_lower_right_column->SetValue(wxString::Format(wxT("%i"),(int)fixedImage.Width() - 1));
00544 
00545                 slider_lower_right_row->SetMax((int)fixedImage.Height() - 1);
00546                 slider_lower_right_row->SetValue((int)fixedImage.Height() - 1);
00547                 edit_lower_right_row->SetValue(wxString::Format(wxT("%i"),(int)fixedImage.Height() - 1));
00548 
00549                 enableGuiElements(true);
00550             }
00551         } else {
00552             check_fix_current_image->Enable(false);
00553             wxBitmap* empty = new wxBitmap(wxImage(480, 360));
00554             image_model->setImage(empty);
00555             image_model->paintNow();
00556         }
00557     }
00558 
00559 }
00560 
00561 void ViewCreatorDialog::onChoiceTestImageSource(wxCommandEvent &event)
00562 {
00563     image_test_sub.shutdown();
00564     choice_test_image->Clear();
00565     image_test->setImage(new wxBitmap(wxImage(480, 360)));
00566     image_test->paintNow();
00567     choice_test_image->Insert(wxString("<No selection>",  wxConvUTF8), 0);
00568     choice_test_image->SetSelection(0);
00569 
00570     switch (choice_test_image_source->GetSelection()) {
00571         case 1:
00572             {
00573                 std::vector<boost::filesystem::path> files;
00574                 boost::filesystem::path input_path(ros::package::getPath("asr_descriptor_surface_based_recognition") + INPUT_FOLDER + "/");
00575                 get_all_files_with_ext(input_path, ".png", files);
00576                 get_all_files_with_ext(input_path, ".jpg", files);
00577                 std::sort(files.begin(), files.end());
00578                 for (unsigned int i = 0; i < files.size(); i++) {
00579                     choice_test_image->AppendString(wxString(files[i].string().c_str(), wxConvUTF8));
00580                 }
00581 
00582                 break;
00583             }
00584         case 2:
00585             {
00586                 std::vector<std::string> image_topics;
00587                 ros::master::V_TopicInfo master_topics;
00588                 ros::master::getTopics(master_topics);
00589 
00590                 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
00591                     const ros::master::TopicInfo& info = *it;
00592                     if (info.datatype == "sensor_msgs/Image") {
00593                         image_topics.push_back(info.name);
00594                     }
00595                 }
00596                 std::sort(image_topics.begin(), image_topics.end());
00597                 for (unsigned int i = 0; i < image_topics.size(); i++) {
00598                     choice_test_image->Insert(wxString(image_topics.at(i).c_str(), wxConvUTF8),i + 1);
00599                 }
00600                 break;
00601             }
00602     }
00603 }
00604 
00605 void ViewCreatorDialog::onChoiceTestImage( wxCommandEvent& event )
00606 {
00607     image_test_sub.shutdown();
00608     if (choice_test_image->GetSelection() > 0) {
00609         if (choice_test_image_source->GetSelection() == 1) {
00610             boost::filesystem::path input_path(ros::package::getPath("asr_descriptor_surface_based_recognition") + INPUT_FOLDER + "/");
00611             wxString filename = wxString(input_path.string().c_str(), wxConvUTF8) + choice_test_image->GetStringSelection();
00612             wxImage image(filename);
00613             image = image.Scale(480, 360);
00614             image_test->setImage(new wxBitmap(image));
00615             image_test->paintNow();
00616         } else if (choice_test_image_source->GetSelection() == 2) {
00617             std::string str = std::string(choice_test_image->GetStringSelection().mb_str());
00618             image_test_sub = nh.subscribe<sensor_msgs::Image>(str, 1, boost::bind(&ViewCreatorDialog::onTestCameraImage, this, _1, false));
00619         }
00620     } else {
00621         image_test->setImage(new wxBitmap(wxImage(480, 360)));
00622         image_test->paintNow();
00623     }
00624 
00625 }
00626 
00627 
00628 
00629 void ViewCreatorDialog::onButtonStartTestClicked(wxCommandEvent &event)
00630 {
00631     if (choice_test_image->GetSelection() > 0) {
00632         if (check_fix_current_image->IsChecked() && fixed_image_available) {
00633             if (desc_model_available) {
00634                 test_running = true;
00635                 label_model_available_value->SetLabel(wxT("Yes"));
00636                 label_score_value->SetLabel(wxT("0.0"));
00637                 score_sum = 0;
00638                 frame_counter = 0;
00639                 feature_sum = 0;
00640                 time_sum = 0;
00641                 label_frame_number_value->SetLabel(wxT("0"));
00642                 label_average_score_value->SetLabel(wxT("0.0"));
00643                 label_model_points_value->SetLabel(wxT("0"));
00644                 label_search_points_value->SetLabel(wxT("0"));
00645                 label_matched_points_value->SetLabel(wxT("0"));
00646                 label_average_matched_points_value->SetLabel(wxT("0"));
00647                 label_time_value->SetLabel(wxT("0.0"));
00648                 label_average_time_value->SetLabel(wxT("0.0"));
00649                 button_start_test->Enable(false);
00650                 button_end_test->Enable(true);
00651                 enableGuiElementsTest(false);
00652 
00653             } else {
00654                 wxMessageDialog *dial = new wxMessageDialog(this,
00655                       wxT("No descriptor model with current parameters available. Do you want to create one? This can take several minutes!"), wxT("Warning"),
00656                       wxYES_NO | wxNO_DEFAULT | wxICON_QUESTION);
00657                   if (dial->ShowModal() == wxID_YES) {
00658                       int row1 = boost::lexical_cast<int>(trim(std::string(edit_upper_left_row->GetValue().mb_str())));
00659                       int column1 = boost::lexical_cast<int>(trim(std::string(edit_upper_left_column->GetValue().mb_str())));
00660                       int row2 = boost::lexical_cast<int>(trim(std::string(edit_lower_right_row->GetValue().mb_str())));
00661                       int column2 = boost::lexical_cast<int>(trim(std::string(edit_lower_right_column->GetValue().mb_str())));
00662 
00663 
00664                       int depth = boost::lexical_cast<int>(trim(std::string(edit_depth->GetValue().mb_str())));
00665                       int number_ferns = boost::lexical_cast<int>(trim(std::string(edit_fern_number->GetValue().mb_str())));
00666                       int patch_size = boost::lexical_cast<int>(trim(std::string(edit_patch_size->GetValue().mb_str())));
00667                       double min_scale = boost::lexical_cast<double>(trim(std::string(edit_min_scale->GetValue().mb_str())));
00668                       double max_scale = boost::lexical_cast<double>(trim(std::string(edit_max_scale->GetValue().mb_str())));
00669                       bool use_color = check_use_color->IsChecked();
00670 
00671                       CreateTestModelDialog *createTestModeldialog = new CreateTestModelDialog(this, &desc_model, fixedImage.CropRectangle1(row1, column1, row2, column2), depth, number_ferns, patch_size, min_scale, max_scale, use_color);
00672                       if (createTestModeldialog ->ShowModal() == wxID_OK) {
00673                           desc_model_available = true;
00674                           test_running = true;
00675                           label_model_available_value->SetLabel(wxT("Yes"));
00676                           label_score_value->SetLabel(wxT("0.0"));
00677                           score_sum = 0;
00678                           feature_sum = 0;
00679                           time_sum = 0;
00680                           frame_counter = 0;
00681                           label_frame_number_value->SetLabel(wxT("0"));
00682                           label_average_score_value->SetLabel(wxT("0.0"));
00683                           label_model_points_value->SetLabel(wxT("0"));
00684                           label_search_points_value->SetLabel(wxT("0"));
00685                           label_matched_points_value->SetLabel(wxT("0"));
00686                           label_average_matched_points_value->SetLabel(wxT("0"));
00687                           button_start_test->Enable(false);
00688                           button_end_test->Enable(true);
00689                           enableGuiElementsTest(false);
00690 
00691                       } else {
00692                           wxMessageDialog *dial = new wxMessageDialog(this,
00693                                 wxT("Error creating model"), wxT("Error"), wxOK | wxICON_ERROR);
00694                              dial->ShowModal();
00695                       }
00696                   }
00697             }
00698         } else {
00699             wxMessageDialog *dial = new wxMessageDialog(this,
00700                   wxT("No image selected!"), wxT("Warning"), wxOK | wxICON_WARNING);
00701                dial->ShowModal();
00702         }
00703     } else {
00704         wxMessageDialog *dial = new wxMessageDialog(this,
00705               wxT("No test image topic selected!"), wxT("Warning"), wxOK | wxICON_WARNING);
00706            dial->ShowModal();
00707     }
00708 }
00709 
00710 void ViewCreatorDialog::onButtonEndTestClicked(wxCommandEvent &event)
00711 {
00712     test_running = false;
00713     button_start_test->Enable(true);
00714     button_end_test->Enable(false);
00715     enableGuiElementsTest(true);
00716 }
00717 
00718 void ViewCreatorDialog::onButtonCancelClicked( wxCommandEvent& event )
00719 {
00720     wxMessageDialog *dial = new wxMessageDialog(this,
00721           wxT("Are you sure you want to cancel?"), wxT("Cancel"),
00722           wxYES_NO | wxNO_DEFAULT | wxICON_QUESTION);
00723       if (dial->ShowModal() == wxID_YES) {
00724           update_timer->Stop();
00725           image_model_sub.shutdown();
00726           image_test_sub.shutdown();
00727           EndModal(wxID_CANCEL);
00728           Destroy();
00729       }
00730 
00731 }
00732 
00733 void ViewCreatorDialog::onButtonSaveClicked( wxCommandEvent& event )
00734 {
00735     if (check_fix_current_image->IsChecked() && fixed_image_available) {
00736 
00737         std::string score_2D_string = trim(std::string(edit_score_2D->GetValue().mb_str()));
00738         if (check_string_redex(score_2D_string, boost::regex("^[0-9]+(\\.[0-9]+)?$"))) {
00739 
00740             std::string vertical_offset_string = trim(std::string(edit_vertical_offset->GetValue().mb_str()));
00741             if (check_string_redex(vertical_offset_string, boost::regex("^[-+]?[0-9]+$"))) {
00742 
00743                 std::string horizontal_offset_string = trim(std::string(edit_horizontal_offset->GetValue().mb_str()));
00744                 if (check_string_redex(horizontal_offset_string, boost::regex("^[-+]?[0-9]+$"))) {
00745 
00746                     std::string depth_string = trim(std::string(edit_depth->GetValue().mb_str()));
00747                     if (check_string_redex(depth_string, boost::regex("^[0-9]+$"))) {
00748 
00749                         std::string number_ferns_string = trim(std::string(edit_fern_number->GetValue().mb_str()));
00750                         if (check_string_redex(number_ferns_string, boost::regex("^[0-9]+$"))) {
00751 
00752                             std::string patch_size_string = trim(std::string(edit_patch_size->GetValue().mb_str()));
00753                             if (check_string_redex(patch_size_string, boost::regex("^[0-9]+$"))) {
00754 
00755                                 std::string min_scale_string = trim(std::string(edit_min_scale->GetValue().mb_str()));
00756                                 if (check_string_redex(min_scale_string, boost::regex("^[0-9]+(\\.[0-9]+)?$"))) {
00757 
00758                                     std::string max_scale_string = trim(std::string(edit_max_scale->GetValue().mb_str()));
00759                                     if (check_string_redex(max_scale_string, boost::regex("^[0-9]+(\\.[0-9]+)?$"))) {
00760 
00761                                         std::string orientation_x_string = trim(std::string(edit_orientation_x->GetValue().mb_str()));
00762                                         if (check_string_redex(orientation_x_string, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
00763 
00764                                             std::string orientation_y_string = trim(std::string(edit_orientation_y->GetValue().mb_str()));
00765                                             if (check_string_redex(orientation_y_string, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
00766 
00767                                                 std::string orientation_z_string = trim(std::string(edit_orientation_z->GetValue().mb_str()));
00768                                                 if (check_string_redex(orientation_z_string, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
00769 
00770                                                     bool axes_valid = true;
00771                                                     if (params->getRotationType() != ROTATIONTYPE_NO_ROTATION) {
00772 
00773                                                         std::string axis_1_x_string = trim(std::string(edit_axis_1_x->GetValue().mb_str()));
00774                                                         if (check_string_redex(axis_1_x_string, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
00775 
00776                                                             std::string axis_1_y_string = trim(std::string(edit_axis_1_y->GetValue().mb_str()));
00777                                                             if (check_string_redex(axis_1_y_string, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
00778 
00779                                                                 std::string axis_1_z_string = trim(std::string(edit_axis_1_z->GetValue().mb_str()));
00780                                                                 if (check_string_redex(axis_1_z_string, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
00781                                                                     axes_valid = true;
00782 
00783                                                                     double axis_1_x = boost::lexical_cast<double>(trim(std::string(edit_axis_1_x->GetValue().mb_str())));
00784                                                                     double axis_1_y = boost::lexical_cast<double>(trim(std::string(edit_axis_1_y->GetValue().mb_str())));
00785                                                                     double axis_1_z = boost::lexical_cast<double>(trim(std::string(edit_axis_1_z->GetValue().mb_str())));
00786                                                                     double axis_1_angle = boost::lexical_cast<double>(trim(std::string(edit_axis_1_angle->GetValue().mb_str())));
00787                                                                     Eigen::Vector3d axis_1(axis_1_x, axis_1_y, axis_1_z);
00788                                                                     params->setAxis1(axis_1);
00789                                                                     params->setAxis1Angle(axis_1_angle);
00790 
00791                                                                     if (params->getRotationType() == ROTATIONTYPE_SPHERE) {
00792 
00793                                                                         std::string axis_2_x_string = trim(std::string(edit_axis_2_x->GetValue().mb_str()));
00794                                                                         if (check_string_redex(axis_2_x_string, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
00795 
00796                                                                             std::string axis_2_y_string = trim(std::string(edit_axis_2_y->GetValue().mb_str()));
00797                                                                             if (check_string_redex(axis_2_y_string, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
00798 
00799                                                                                 std::string axis_2_z_string = trim(std::string(edit_axis_2_z->GetValue().mb_str()));
00800                                                                                 if (check_string_redex(axis_2_z_string, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
00801                                                                                     axes_valid = true;
00802 
00803                                                                                     double axis_2_x = boost::lexical_cast<double>(trim(std::string(edit_axis_2_x->GetValue().mb_str())));
00804                                                                                     double axis_2_y = boost::lexical_cast<double>(trim(std::string(edit_axis_2_y->GetValue().mb_str())));
00805                                                                                     double axis_2_z = boost::lexical_cast<double>(trim(std::string(edit_axis_2_z->GetValue().mb_str())));
00806                                                                                     double axis_2_angle = boost::lexical_cast<double>(trim(std::string(edit_axis_2_angle->GetValue().mb_str())));
00807                                                                                     Eigen::Vector3d axis_2(axis_2_x, axis_2_y, axis_2_z);
00808                                                                                     params->setAxis2(axis_2);
00809                                                                                     params->setAxis2Angle(axis_2_angle);
00810 
00811 
00812                                                                                 } else {
00813                                                                                     wxMessageDialog *dial = new wxMessageDialog(this,
00814                                                                                            wxT("Axis 2 (z) is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00815                                                                                        dial->ShowModal();
00816                                                                                     axes_valid = false;
00817                                                                                 }
00818                                                                             } else {
00819                                                                                 wxMessageDialog *dial = new wxMessageDialog(this,
00820                                                                                        wxT("Axis 2 (y) is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00821                                                                                    dial->ShowModal();
00822                                                                                 axes_valid = false;
00823                                                                             }
00824                                                                         } else {
00825                                                                             wxMessageDialog *dial = new wxMessageDialog(this,
00826                                                                                    wxT("Axis 2 (x) is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00827                                                                                dial->ShowModal();
00828                                                                             axes_valid = false;
00829                                                                         }
00830                                                                     }
00831 
00832 
00833                                                                 } else {
00834                                                                     wxMessageDialog *dial = new wxMessageDialog(this,
00835                                                                            wxT("Axis 1 (z) is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00836                                                                        dial->ShowModal();
00837                                                                     axes_valid = false;
00838                                                                 }
00839                                                             } else {
00840                                                                 wxMessageDialog *dial = new wxMessageDialog(this,
00841                                                                        wxT("Axis 1 (y) is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00842                                                                    dial->ShowModal();
00843                                                                 axes_valid = false;
00844                                                             }
00845                                                         } else {
00846                                                             wxMessageDialog *dial = new wxMessageDialog(this,
00847                                                                    wxT("Axis 1 (x) is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00848                                                                dial->ShowModal();
00849                                                             axes_valid = false;
00850                                                         }
00851                                                     }
00852                                                     if (axes_valid) {
00853                                                         //all strings are valid!
00854                                                         int row1 = boost::lexical_cast<int>(trim(std::string(edit_upper_left_row->GetValue().mb_str())));
00855                                                         int column1 = boost::lexical_cast<int>(trim(std::string(edit_upper_left_column->GetValue().mb_str())));
00856                                                         int row2 = boost::lexical_cast<int>(trim(std::string(edit_lower_right_row->GetValue().mb_str())));
00857                                                         int column2 = boost::lexical_cast<int>(trim(std::string(edit_lower_right_column->GetValue().mb_str())));
00858                                                         params->setImage(fixedImage.CropRectangle1(row1, column1, row2, column2));
00859                                                         params->setOriginalImage(fixedImage);
00860                                                         params->setImageBounds(row1, column1, row2, column2);
00861                                                         params->setIsInvertible(check_invertable->GetValue());
00862                                                         params->setUserColor(check_use_color->GetValue());
00863                                                         double orientation_x = boost::lexical_cast<double>(trim(std::string(edit_orientation_x->GetValue().mb_str())));
00864                                                         double orientation_y = boost::lexical_cast<double>(trim(std::string(edit_orientation_y->GetValue().mb_str())));
00865                                                         double orientation_z = boost::lexical_cast<double>(trim(std::string(edit_orientation_z->GetValue().mb_str())));
00866                                                         Eigen::Vector3d orientation(orientation_x, orientation_y, orientation_z);
00867                                                         params->setOrientation(orientation);
00868                                                         double score_2D = boost::lexical_cast<double>(trim(std::string(edit_score_2D->GetValue().mb_str())));
00869                                                         params->setScore2D(score_2D);
00870                                                         int vertical_offset = boost::lexical_cast<int>(trim(std::string(edit_vertical_offset->GetValue().mb_str())));
00871                                                         params->setVerticalOffset(vertical_offset);
00872                                                         int horizontal_offset = boost::lexical_cast<int>(trim(std::string(edit_horizontal_offset->GetValue().mb_str())));
00873                                                         params->setHorizontalOffset(horizontal_offset);
00874                                                         int depth = boost::lexical_cast<int>(trim(std::string(edit_depth->GetValue().mb_str())));
00875                                                         params->setDepth(depth);
00876                                                         int number_ferns = boost::lexical_cast<int>(trim(std::string(edit_fern_number->GetValue().mb_str())));
00877                                                         params->setNumberFerns(number_ferns);
00878                                                         int patch_size = boost::lexical_cast<int>(trim(std::string(edit_patch_size->GetValue().mb_str())));
00879                                                         params->setPatchSize(patch_size);
00880                                                         double min_scale = boost::lexical_cast<double>(trim(std::string(edit_min_scale->GetValue().mb_str())));
00881                                                         params->setMinScale(min_scale);
00882                                                         double max_scale = boost::lexical_cast<double>(trim(std::string(edit_max_scale->GetValue().mb_str())));
00883                                                         params->setMaxScale(max_scale);
00884 
00885 
00886                                                         params->setIsValid(true);
00887 
00888                                                         update_timer->Stop();
00889                                                         image_model_sub.shutdown();
00890                                                         image_test_sub.shutdown();
00891                                                         EndModal(wxID_SAVE);
00892                                                         Destroy();
00893 
00894 
00895 
00896 
00897                                                     }
00898                                                 } else {
00899                                                     wxMessageDialog *dial = new wxMessageDialog(this,
00900                                                            wxT("Orientation (z) is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00901                                                        dial->ShowModal();
00902                                                 }
00903                                             } else {
00904                                                 wxMessageDialog *dial = new wxMessageDialog(this,
00905                                                        wxT("Orientation (y) is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00906                                                    dial->ShowModal();
00907                                             }
00908                                         } else {
00909                                             wxMessageDialog *dial = new wxMessageDialog(this,
00910                                                    wxT("Orientation (x) is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00911                                                dial->ShowModal();
00912                                         }
00913                                     } else {
00914                                         wxMessageDialog *dial = new wxMessageDialog(this,
00915                                               wxT("Max. scale is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00916                                            dial->ShowModal();
00917                                     }
00918                                 } else {
00919                                     wxMessageDialog *dial = new wxMessageDialog(this,
00920                                           wxT("Min. scale is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00921                                        dial->ShowModal();
00922                                 }
00923                             } else {
00924                                 wxMessageDialog *dial = new wxMessageDialog(this,
00925                                       wxT("Patch size is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00926                                    dial->ShowModal();
00927                             }
00928                         } else {
00929                             wxMessageDialog *dial = new wxMessageDialog(this,
00930                                   wxT("Fern number is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00931                                dial->ShowModal();
00932                         }
00933                     } else {
00934                         wxMessageDialog *dial = new wxMessageDialog(this,
00935                               wxT("Depth is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00936                            dial->ShowModal();
00937                     }
00938                 } else {
00939                     wxMessageDialog *dial = new wxMessageDialog(this,
00940                           wxT("Horizontal offset is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00941                        dial->ShowModal();
00942                 }
00943             } else {
00944                 wxMessageDialog *dial = new wxMessageDialog(this,
00945                       wxT("Vertical offset is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00946                    dial->ShowModal();
00947             }
00948         } else {
00949             wxMessageDialog *dial = new wxMessageDialog(this,
00950                   wxT("Score is not valid!"), wxT("Error"), wxOK | wxICON_ERROR);
00951                dial->ShowModal();
00952         }
00953     } else {
00954         wxMessageDialog *dial = new wxMessageDialog(this,
00955               wxT("No image selected!"), wxT("Error"), wxOK | wxICON_ERROR);
00956            dial->ShowModal();
00957     }
00958 }
00959 
00960 void ViewCreatorDialog::onCheckUseCurrentImage(wxCommandEvent &event)
00961 {
00962     desc_model_available = false;
00963     label_model_available_value->SetLabel(wxT("No"));
00964     if (check_fix_current_image->IsChecked()) {
00965 
00966     } else {
00967 
00968         fixed_image_available = false;
00969         enableGuiElements(false);
00970     }
00971 }
00972 
00973 void ViewCreatorDialog::onEditTextUpperLeftRow(wxFocusEvent &event)
00974 {
00975 
00976     std::string upperLeftRowString = trim(std::string(edit_upper_left_row->GetValue().mb_str()));
00977     std::string lowerRightRowString = trim(std::string(edit_lower_right_row->GetValue().mb_str()));
00978 
00979     if (check_string_redex(upperLeftRowString, boost::regex("^[0-9]+$"))) {
00980         if (check_string_redex(lowerRightRowString, boost::regex("^[0-9]+$"))) {
00981             int upperLeftRow = boost::lexical_cast<int>(upperLeftRowString);
00982             int lowerRightRow = boost::lexical_cast<int>(lowerRightRowString);
00983             if ((upperLeftRow >= 0) && (upperLeftRow <= slider_lower_right_row->GetMax() - 2)) {
00984                 slider_upper_left_row->SetValue(upperLeftRow);
00985                 if (lowerRightRow <= upperLeftRow) {
00986                     edit_lower_right_row->SetValue(wxString::Format(wxT("%i"), upperLeftRow + 1));
00987                     slider_lower_right_row->SetValue(upperLeftRow + 1);
00988                 }
00989             } else {
00990                 edit_upper_left_row->SetValue(wxString::Format(wxT("%i"), 0));
00991                 slider_upper_left_row->SetValue(0);
00992             }
00993         }
00994     } else {
00995         edit_upper_left_row->SetValue(wxString::Format(wxT("%i"), 0));
00996         slider_upper_left_row->SetValue(0);
00997     }
00998 
00999     updateImageOnCrop();
01000     desc_model_available = false;
01001     label_model_available_value->SetLabel(wxT("No"));
01002 }
01003 
01004 void ViewCreatorDialog::onEditTextUpperLeftColumn(wxFocusEvent &event)
01005 {
01006     std::string upperLeftColumnString = trim(std::string(edit_upper_left_column->GetValue().mb_str()));
01007     std::string lowerRightColumnString = trim(std::string(edit_lower_right_column->GetValue().mb_str()));
01008 
01009     if (check_string_redex(upperLeftColumnString, boost::regex("^[0-9]+$"))) {
01010         if (check_string_redex(lowerRightColumnString, boost::regex("^[0-9]+$"))) {
01011             int upperLeftColumn = boost::lexical_cast<int>(upperLeftColumnString);
01012             int lowerRightColumn = boost::lexical_cast<int>(lowerRightColumnString);
01013             if ((upperLeftColumn >= 0) && (upperLeftColumn <= slider_lower_right_column->GetMax() - 2)) {
01014                 slider_upper_left_column->SetValue(upperLeftColumn);
01015                 if (lowerRightColumn <= upperLeftColumn) {
01016                     edit_lower_right_column->SetValue(wxString::Format(wxT("%i"), upperLeftColumn + 1));
01017                     slider_lower_right_column->SetValue(upperLeftColumn + 1);
01018                 }
01019             } else {
01020                 edit_upper_left_column->SetValue(wxString::Format(wxT("%i"), 0));
01021                 slider_upper_left_column->SetValue(0);
01022             }
01023         }
01024     } else {
01025         edit_upper_left_column->SetValue(wxString::Format(wxT("%i"), 0));
01026         slider_upper_left_column->SetValue(0);
01027     }
01028 
01029     updateImageOnCrop();
01030     desc_model_available = false;
01031     label_model_available_value->SetLabel(wxT("No"));
01032 }
01033 
01034 
01035 
01036 void ViewCreatorDialog::onEditTextLowerRightRow(wxFocusEvent &event)
01037 {
01038     std::string lowerRightRowString = trim(std::string(edit_lower_right_row->GetValue().mb_str()));
01039     std::string upperLeftRowString = trim(std::string(edit_upper_left_row->GetValue().mb_str()));
01040 
01041     if (check_string_redex(lowerRightRowString, boost::regex("^[0-9]+$"))) {
01042         if (check_string_redex(upperLeftRowString, boost::regex("^[0-9]+$"))) {
01043             int lowerRightRow = boost::lexical_cast<int>(lowerRightRowString);
01044             int upperLeftRow = boost::lexical_cast<int>(upperLeftRowString);
01045             if ((lowerRightRow <= slider_lower_right_row->GetMax()) && (lowerRightRow >= 2)) {
01046                 slider_lower_right_row->SetValue(lowerRightRow);
01047                 if (upperLeftRow >= lowerRightRow) {
01048                     edit_upper_left_row->SetValue(wxString::Format(wxT("%i"), lowerRightRow - 1));
01049                     slider_upper_left_row->SetValue(lowerRightRow - 1);
01050                 }
01051             } else {
01052                 edit_lower_right_row->SetValue(wxString::Format(wxT("%i"), slider_lower_right_row->GetMax()));
01053                 slider_lower_right_row->SetValue(slider_lower_right_row->GetMax());
01054             }
01055         }
01056     } else {
01057         edit_lower_right_row->SetValue(wxString::Format(wxT("%i"), slider_lower_right_row->GetMax()));
01058         slider_lower_right_row->SetValue(slider_lower_right_row->GetMax());
01059     }
01060 
01061     updateImageOnCrop();
01062     desc_model_available = false;
01063     label_model_available_value->SetLabel(wxT("No"));
01064 }
01065 
01066 
01067 void ViewCreatorDialog::onEditTextLowerRightColumn(wxFocusEvent &event)
01068 {
01069     std::string lowerRightColumnString = trim(std::string(edit_lower_right_column->GetValue().mb_str()));
01070     std::string upperLeftColumnString = trim(std::string(edit_upper_left_column->GetValue().mb_str()));
01071 
01072     if (check_string_redex(lowerRightColumnString, boost::regex("^[0-9]+$"))) {
01073         if (check_string_redex(upperLeftColumnString, boost::regex("^[0-9]+$"))) {
01074             int lowerRightColumn = boost::lexical_cast<int>(lowerRightColumnString);
01075             int upperLeftColumn = boost::lexical_cast<int>(upperLeftColumnString);
01076             if ((lowerRightColumn <= slider_lower_right_column->GetMax()) && (lowerRightColumn >= 2)) {
01077                 slider_lower_right_column->SetValue(lowerRightColumn);
01078                 if (upperLeftColumn >= lowerRightColumn) {
01079                     edit_upper_left_column->SetValue(wxString::Format(wxT("%i"), lowerRightColumn - 1));
01080                     slider_upper_left_column->SetValue(lowerRightColumn - 1);
01081                 }
01082             } else {
01083                 edit_lower_right_column->SetValue(wxString::Format(wxT("%i"), slider_lower_right_column->GetMax()));
01084                 slider_lower_right_column->SetValue(slider_lower_right_column->GetMax());
01085             }
01086         }
01087     } else {
01088         edit_lower_right_column->SetValue(wxString::Format(wxT("%i"), slider_lower_right_column->GetMax()));
01089         slider_lower_right_column->SetValue(slider_lower_right_column->GetMax());
01090     }
01091 
01092     updateImageOnCrop();
01093     desc_model_available = false;
01094     label_model_available_value->SetLabel(wxT("No"));
01095 }
01096 
01097 void ViewCreatorDialog::onSlideUpperLeftRow(wxScrollEvent &event)
01098 {
01099     int upperLeftRowValue = slider_upper_left_row->GetValue();
01100     if (upperLeftRowValue <= slider_upper_left_row->GetMax() - 2) {
01101         edit_upper_left_row->SetValue(wxString::Format(wxT("%i"), upperLeftRowValue));
01102         slider_upper_left_row->SetValue(upperLeftRowValue);
01103     } else {
01104         edit_upper_left_row->SetValue(wxString::Format(wxT("%i"), slider_upper_left_row->GetMax() - 2));
01105         slider_upper_left_row->SetValue(slider_upper_left_row->GetMax() - 2);
01106     }
01107 
01108     upperLeftRowValue = boost::lexical_cast<int>(trim(std::string(edit_upper_left_row->GetValue().mb_str())));
01109     if (slider_lower_right_row->GetValue() <= upperLeftRowValue) {
01110         edit_lower_right_row->SetValue(wxString::Format(wxT("%i"), upperLeftRowValue + 1));
01111         slider_lower_right_row->SetValue(upperLeftRowValue + 1);
01112     }
01113 
01114     updateImageOnCrop();
01115     desc_model_available = false;
01116     label_model_available_value->SetLabel(wxT("No"));
01117 }
01118 
01119 void ViewCreatorDialog::onSlideUpperLeftColumn(wxScrollEvent &event)
01120 {
01121     int upperLeftColumnValue = slider_upper_left_column->GetValue();
01122     if (upperLeftColumnValue <= slider_upper_left_column->GetMax() - 2) {
01123         edit_upper_left_column->SetValue(wxString::Format(wxT("%i"), upperLeftColumnValue));
01124         slider_upper_left_column->SetValue(upperLeftColumnValue);
01125     } else {
01126         edit_upper_left_column->SetValue(wxString::Format(wxT("%i"), slider_upper_left_column->GetMax() - 2));
01127         slider_upper_left_column->SetValue(slider_upper_left_column->GetMax() - 2);
01128     }
01129 
01130     upperLeftColumnValue = boost::lexical_cast<int>(trim(std::string(edit_upper_left_column->GetValue().mb_str())));
01131     if (slider_lower_right_column->GetValue() <= upperLeftColumnValue) {
01132         edit_lower_right_column->SetValue(wxString::Format(wxT("%i"), upperLeftColumnValue + 1));
01133         slider_lower_right_column->SetValue(upperLeftColumnValue + 1);
01134     }
01135 
01136     updateImageOnCrop();
01137     desc_model_available = false;
01138     label_model_available_value->SetLabel(wxT("No"));
01139 }
01140 
01141 void ViewCreatorDialog::onSlideLowerRightRow(wxScrollEvent &event)
01142 {
01143     int lowerRightRowValue = slider_lower_right_row->GetValue();
01144     if (lowerRightRowValue >= 2) {
01145         edit_lower_right_row->SetValue(wxString::Format(wxT("%i"), lowerRightRowValue));
01146         slider_lower_right_row->SetValue(lowerRightRowValue);
01147     } else {
01148         edit_lower_right_row->SetValue(wxString::Format(wxT("%i"), 2));
01149         slider_lower_right_row->SetValue(2);
01150     }
01151 
01152     lowerRightRowValue = boost::lexical_cast<int>(trim(std::string(edit_lower_right_row->GetValue().mb_str())));
01153     if (slider_upper_left_row->GetValue() >= lowerRightRowValue) {
01154         edit_upper_left_row->SetValue(wxString::Format(wxT("%i"), lowerRightRowValue - 1));
01155         slider_upper_left_row->SetValue(lowerRightRowValue - 1);
01156     }
01157 
01158     updateImageOnCrop();
01159     desc_model_available = false;
01160     label_model_available_value->SetLabel(wxT("No"));
01161 }
01162 
01163 void ViewCreatorDialog::onSlideLowerRightColumn(wxScrollEvent &event)
01164 {
01165     int lowerRightColumnValue = slider_lower_right_column->GetValue();
01166     if (lowerRightColumnValue >= 2) {
01167         edit_lower_right_column->SetValue(wxString::Format(wxT("%i"), lowerRightColumnValue));
01168         slider_lower_right_column->SetValue(lowerRightColumnValue);
01169     } else {
01170         edit_lower_right_column->SetValue(wxString::Format(wxT("%i"), 2));
01171         slider_lower_right_column->SetValue(2);
01172     }
01173 
01174     lowerRightColumnValue = boost::lexical_cast<int>(trim(std::string(edit_lower_right_column->GetValue().mb_str())));
01175     if (slider_upper_left_column->GetValue() >= lowerRightColumnValue) {
01176         edit_upper_left_column->SetValue(wxString::Format(wxT("%i"), lowerRightColumnValue - 1));
01177         slider_upper_left_column->SetValue(lowerRightColumnValue - 1);
01178     }
01179 
01180     updateImageOnCrop();
01181     desc_model_available = false;
01182     label_model_available_value->SetLabel(wxT("No"));
01183 }
01184 
01185 void ViewCreatorDialog::onEditTextUpperLeftRowEnter(wxCommandEvent &event) {
01186     wxFocusEvent evt;
01187     onEditTextUpperLeftRow(evt);
01188 }
01189 
01190 void ViewCreatorDialog::onEditTextUpperLeftColumnEnter(wxCommandEvent &event) {
01191     wxFocusEvent evt;
01192     onEditTextUpperLeftColumn(evt);
01193 }
01194 
01195 void ViewCreatorDialog::onEditTextLowerRightRowEnter(wxCommandEvent &event) {
01196     wxFocusEvent evt;
01197     onEditTextLowerRightRow(evt);
01198 }
01199 
01200 void ViewCreatorDialog::onEditTextLowerRightColumnEnter(wxCommandEvent &event) {
01201     wxFocusEvent evt;
01202     onEditTextLowerRightColumn(evt);
01203 }
01204 
01205 void ViewCreatorDialog::onEditTextOrientationX(wxFocusEvent &event)
01206 {
01207     std::string orientation_x = trim(std::string(edit_orientation_x->GetValue().mb_str()));
01208     if (!check_string_redex(orientation_x, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
01209         edit_orientation_x->SetValue(wxT("1.0"));
01210     }
01211 }
01212 
01213 void ViewCreatorDialog::onEditTextOrientationY(wxFocusEvent &event)
01214 {
01215     std::string orientation_y = trim(std::string(edit_orientation_y->GetValue().mb_str()));
01216     if (!check_string_redex(orientation_y, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
01217         edit_orientation_y->SetValue(wxT("0.0"));
01218     }
01219 }
01220 
01221 void ViewCreatorDialog::onEditTextOrientationZ(wxFocusEvent &event)
01222 {
01223     std::string orientation_z = trim(std::string(edit_orientation_z->GetValue().mb_str()));
01224     if (!check_string_redex(orientation_z, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
01225         edit_orientation_z->SetValue(wxT("0.0"));
01226     }
01227 }
01228 
01229 void ViewCreatorDialog::onEditTextScore(wxFocusEvent &event)
01230 {
01231     std::string score = trim(std::string(edit_score_2D->GetValue().mb_str()));
01232     if (!check_string_redex(score, boost::regex("^[0-9]+(\\.[0-9]+)?$"))) {
01233         edit_score_2D->SetValue(wxT("0.2"));
01234     }
01235 }
01236 
01237 void ViewCreatorDialog::onEditTextVerticalOffset(wxFocusEvent &event)
01238 {
01239     std::string vertical_offset = trim(std::string(edit_vertical_offset->GetValue().mb_str()));
01240     if (!check_string_redex(vertical_offset, boost::regex("^[-+]?[0-9]+$$"))) {
01241         edit_vertical_offset->SetValue(wxT("0"));
01242     }
01243 }
01244 
01245 void ViewCreatorDialog::onEditTextHorizontalOffset(wxFocusEvent &event)
01246 {
01247     std::string horizontal_offset = trim(std::string(edit_horizontal_offset->GetValue().mb_str()));
01248     if (!check_string_redex(horizontal_offset, boost::regex("^[-+]?[0-9]+$"))) {
01249         edit_horizontal_offset->SetValue(wxT("0"));
01250     }
01251 }
01252 
01253 void ViewCreatorDialog::onEditTextDepth(wxFocusEvent &event)
01254 {
01255     std::string depth_string = trim(std::string(edit_depth->GetValue().mb_str()));
01256     if (check_string_redex(depth_string, boost::regex("^[0-9]+$"))) {
01257         int depth = boost::lexical_cast<int>(trim(std::string(edit_depth->GetValue().mb_str())));
01258         if ((depth <= 0) || (depth > 15)) {
01259             edit_depth->SetValue(wxT("8"));
01260         }
01261     } else {
01262         edit_depth->SetValue(wxT("8"));
01263     }
01264 
01265     if (desc_model_available) {
01266         HalconCpp::HTuple detName, detValue, descName, descParam;
01267         desc_model.GetDescriptorModelParams(&detName, &detValue, &descName, &descParam);
01268         int curr_depth = boost::lexical_cast<int>(trim(std::string(edit_depth->GetValue().mb_str())));
01269         if (curr_depth != (int)descParam[0]) {
01270             desc_model_available = false;
01271             label_model_available_value->SetLabel(wxT("No"));
01272         }
01273     }
01274 }
01275 
01276 void ViewCreatorDialog::onEditTextFernNumber(wxFocusEvent &event)
01277 {
01278     std::string fern_number_string = trim(std::string(edit_fern_number->GetValue().mb_str()));
01279     if (check_string_redex(fern_number_string, boost::regex("^[0-9]+$"))) {
01280         int fern_number = boost::lexical_cast<int>(trim(std::string(edit_fern_number->GetValue().mb_str())));
01281         if ((fern_number <= 0) || (fern_number > 500)) {
01282             edit_fern_number->SetValue(wxT("50"));
01283         }
01284     } else {
01285         edit_fern_number->SetValue(wxT("50"));
01286     }
01287 
01288     if (desc_model_available) {
01289         HalconCpp::HTuple detName, detValue, descName, descParam;
01290         desc_model.GetDescriptorModelParams(&detName, &detValue, &descName, &descParam);
01291         int curr_ferns = boost::lexical_cast<int>(trim(std::string(edit_fern_number->GetValue().mb_str())));
01292         if (curr_ferns != (int)descParam[1]) {
01293             desc_model_available = false;
01294             label_model_available_value->SetLabel(wxT("No"));
01295         }
01296     }
01297 }
01298 
01299 void ViewCreatorDialog::onEditTextPatchSize(wxFocusEvent &event)
01300 {
01301     std::string patch_size_string = trim(std::string(edit_patch_size->GetValue().mb_str()));
01302     if (check_string_redex(patch_size_string, boost::regex("^[0-9]+$"))) {
01303         int patch_size = boost::lexical_cast<int>(trim(std::string(edit_patch_size->GetValue().mb_str())));
01304         if ((patch_size <= 10) || (patch_size > 40) || (patch_size % 2 == 0)) {
01305             edit_patch_size->SetValue(wxT("17"));
01306         }
01307     } else {
01308         edit_patch_size->SetValue(wxT("17"));
01309     }
01310 
01311     if (desc_model_available) {
01312         HalconCpp::HTuple detName, detValue, descName, descParam;
01313         desc_model.GetDescriptorModelParams(&detName, &detValue, &descName, &descParam);
01314         int curr_patches = boost::lexical_cast<int>(trim(std::string(edit_patch_size->GetValue().mb_str())));
01315         if (curr_patches != (int)descParam[2]) {
01316             desc_model_available = false;
01317             label_model_available_value->SetLabel(wxT("No"));
01318         }
01319     }
01320 }
01321 
01322 void ViewCreatorDialog::onEditTextMinScale(wxFocusEvent &event)
01323 {
01324     std::string min_scale_string = trim(std::string(edit_min_scale->GetValue().mb_str()));
01325     if (check_string_redex(min_scale_string, boost::regex("^[0-9]+(\\.[0-9]+)?$"))) {
01326         double min_scale = boost::lexical_cast<double>(trim(std::string(edit_min_scale->GetValue().mb_str())));
01327         if ((min_scale < 0.2) || (min_scale > 1.2)) {
01328             edit_min_scale->SetValue(wxT("0.6"));
01329         }
01330     } else {
01331         edit_min_scale->SetValue(wxT("0.6"));
01332     }
01333 
01334     if (desc_model_available) {
01335         HalconCpp::HTuple detName, detValue, descName, descParam;
01336         desc_model.GetDescriptorModelParams(&detName, &detValue, &descName, &descParam);
01337         double curr_min_scale = boost::lexical_cast<double>(trim(std::string(edit_min_scale->GetValue().mb_str())));
01338         if (curr_min_scale != (double)descParam[8]) {
01339             desc_model_available = false;
01340             label_model_available_value->SetLabel(wxT("No"));
01341         }
01342     }
01343 }
01344 
01345 void ViewCreatorDialog::onEditTextMaxScale(wxFocusEvent &event)
01346 {
01347     std::string max_scale_string = trim(std::string(edit_max_scale->GetValue().mb_str()));
01348     if (check_string_redex(max_scale_string, boost::regex("^[0-9]+(\\.[0-9]+)?$"))) {
01349         double max_scale = boost::lexical_cast<double>(trim(std::string(edit_max_scale->GetValue().mb_str())));
01350         if ((max_scale < 0.8) || (max_scale > 1.8)) {
01351             edit_max_scale->SetValue(wxT("1.1"));
01352         }
01353     } else {
01354         edit_max_scale->SetValue(wxT("1.1"));
01355     }
01356 
01357     if (desc_model_available) {
01358         HalconCpp::HTuple detName, detValue, descName, descParam;
01359         desc_model.GetDescriptorModelParams(&detName, &detValue, &descName, &descParam);
01360         double curr_max_scale = boost::lexical_cast<double>(trim(std::string(edit_max_scale->GetValue().mb_str())));
01361         if (curr_max_scale != (double)descParam[9]) {
01362             desc_model_available = false;
01363             label_model_available_value->SetLabel(wxT("No"));
01364         }
01365     }
01366 }
01367 
01368 void ViewCreatorDialog::onCheckUpsideDown(wxCommandEvent &event)
01369 {
01370     //Do nothing
01371 }
01372 
01373 void ViewCreatorDialog::onCheckUseColor(wxCommandEvent &event)
01374 {
01375     desc_model_available = false;
01376     label_model_available_value->SetLabel(wxT("No"));
01377 }
01378 
01379 void ViewCreatorDialog::onEditTextAxis1X(wxFocusEvent &event)
01380 {
01381     std::string axis_1_x = trim(std::string(edit_axis_1_x->GetValue().mb_str()));
01382     if (!check_string_redex(axis_1_x, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
01383         edit_axis_1_x->SetValue(wxT("0.0"));
01384     }
01385 }
01386 
01387 void ViewCreatorDialog::onEditTextAxis1Y(wxFocusEvent &event)
01388 {
01389     std::string axis_1_y = trim(std::string(edit_axis_1_y->GetValue().mb_str()));
01390     if (!check_string_redex(axis_1_y, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
01391         edit_axis_1_y->SetValue(wxT("1.0"));
01392     }
01393 }
01394 
01395 void ViewCreatorDialog::onEditTextAxis1Z(wxFocusEvent &event)
01396 {
01397     std::string axis_1_z = trim(std::string(edit_axis_1_z->GetValue().mb_str()));
01398     if (!check_string_redex(axis_1_z, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
01399         edit_axis_1_z->SetValue(wxT("0.0"));
01400     }
01401 }
01402 
01403 void ViewCreatorDialog::onEditTextAxis1Angle(wxFocusEvent &event)
01404 {
01405     std::string axis_1_angle = trim(std::string(edit_axis_1_angle->GetValue().mb_str()));
01406     if (check_string_redex(axis_1_angle, boost::regex("^[0-9]+(\\.[0-9]+)?$"))) {
01407         double angle = boost::lexical_cast<double>(trim(std::string(edit_axis_1_angle->GetValue().mb_str())));
01408         if ((angle <= 0) || (angle >= 360)) {
01409             edit_axis_1_angle->SetValue(wxT("1.0"));
01410         }
01411     } else {
01412         edit_axis_1_angle->SetValue(wxT("1.0"));
01413     }
01414 }
01415 
01416 void ViewCreatorDialog::onEditTextAxis2X(wxFocusEvent &event)
01417 {
01418     std::string axis_2_x = trim(std::string(edit_axis_2_x->GetValue().mb_str()));
01419     if (!check_string_redex(axis_2_x, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
01420         edit_axis_2_x->SetValue(wxT("0.0"));
01421     }
01422 }
01423 
01424 void ViewCreatorDialog::onEditTextAxis2Y(wxFocusEvent &event)
01425 {
01426     std::string axis_2_y = trim(std::string(edit_axis_2_y->GetValue().mb_str()));
01427     if (!check_string_redex(axis_2_y, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
01428         edit_axis_2_y->SetValue(wxT("0.0"));
01429     }
01430 }
01431 
01432 void ViewCreatorDialog::onEditTextAxis2Z(wxFocusEvent &event)
01433 {
01434     std::string axis_2_z = trim(std::string(edit_axis_2_z->GetValue().mb_str()));
01435     if (!check_string_redex(axis_2_z, boost::regex("^[-+]?[0-9]+(\\.[0-9]+)?$"))) {
01436         edit_axis_2_z->SetValue(wxT("-1.0"));
01437     }
01438 }
01439 
01440 void ViewCreatorDialog::onEditTextAxis2Angle(wxFocusEvent &event)
01441 {
01442     std::string axis_2_angle = trim(std::string(edit_axis_2_angle->GetValue().mb_str()));
01443     if (check_string_redex(axis_2_angle, boost::regex("^[0-9]+(\\.[0-9]+)?$"))) {
01444         double angle = boost::lexical_cast<double>(trim(std::string(edit_axis_2_angle->GetValue().mb_str())));
01445         if ((angle <= 0) || (angle >= 360)) {
01446             edit_axis_2_angle->SetValue(wxT("1.0"));
01447         }
01448     } else {
01449         edit_axis_2_angle->SetValue(wxT("1.0"));
01450     }
01451 }
01452 
01453 
01454 
01455 void ViewCreatorDialog::onEditTextOrientationXEnter(wxCommandEvent &event)
01456 {
01457     wxFocusEvent evt;
01458     onEditTextOrientationX(evt);
01459 }
01460 
01461 void ViewCreatorDialog::onEditTextOrientationYEnter(wxCommandEvent &event)
01462 {
01463     wxFocusEvent evt;
01464     onEditTextOrientationY(evt);
01465 }
01466 
01467 void ViewCreatorDialog::onEditTextOrientationZEnter(wxCommandEvent &event)
01468 {
01469     wxFocusEvent evt;
01470     onEditTextOrientationZ(evt);
01471 }
01472 
01473 void ViewCreatorDialog::onEditTextScoreEnter(wxCommandEvent &event)
01474 {
01475     wxFocusEvent evt;
01476     onEditTextScore(evt);
01477 }
01478 
01479 void ViewCreatorDialog::onEditTextVerticalOffsetEnter(wxCommandEvent &event)
01480 {
01481     wxFocusEvent evt;
01482     onEditTextVerticalOffset(evt);
01483 }
01484 
01485 void ViewCreatorDialog::onEditTextHorizontalOffsetEnter(wxCommandEvent &event)
01486 {
01487     wxFocusEvent evt;
01488     onEditTextHorizontalOffset(evt);
01489 }
01490 
01491 void ViewCreatorDialog::onEditTextDepthEnter(wxCommandEvent &event)
01492 {
01493     wxFocusEvent evt;
01494     onEditTextDepth(evt);
01495 }
01496 
01497 void ViewCreatorDialog::onEditTextFernNumberEnter(wxCommandEvent &event)
01498 {
01499     wxFocusEvent evt;
01500     onEditTextFernNumber(evt);
01501 }
01502 
01503 void ViewCreatorDialog::onEditTextPatchSizeEnter(wxCommandEvent &event)
01504 {
01505     wxFocusEvent evt;
01506     onEditTextPatchSize(evt);
01507 }
01508 
01509 void ViewCreatorDialog::onEditTextMinScaleEnter(wxCommandEvent &event)
01510 {
01511     wxFocusEvent evt;
01512     onEditTextMinScale(evt);
01513 }
01514 
01515 void ViewCreatorDialog::onEditTextMaxScaleEnter(wxCommandEvent &event)
01516 {
01517     wxFocusEvent evt;
01518     onEditTextMaxScale(evt);
01519 }
01520 
01521 void ViewCreatorDialog::onEditTextAxis1XEnter(wxCommandEvent &event)
01522 {
01523     wxFocusEvent evt;
01524     onEditTextAxis1X(evt);
01525 }
01526 
01527 void ViewCreatorDialog::onEditTextAxis1YEnter(wxCommandEvent &event)
01528 {
01529     wxFocusEvent evt;
01530     onEditTextAxis1Y(evt);
01531 }
01532 
01533 void ViewCreatorDialog::onEditTextAxis1ZEnter(wxCommandEvent &event)
01534 {
01535     wxFocusEvent evt;
01536     onEditTextAxis1Z(evt);
01537 }
01538 
01539 void ViewCreatorDialog::onEditTextAxis1AngleEnter(wxCommandEvent &event)
01540 {
01541     wxFocusEvent evt;
01542     onEditTextAxis1Angle(evt);
01543 }
01544 
01545 void ViewCreatorDialog::onEditTextAxis2XEnter(wxCommandEvent &event)
01546 {
01547     wxFocusEvent evt;
01548     onEditTextAxis2X(evt);
01549 }
01550 
01551 void ViewCreatorDialog::onEditTextAxis2YEnter(wxCommandEvent &event)
01552 {
01553     wxFocusEvent evt;
01554     onEditTextAxis2Y(evt);
01555 }
01556 
01557 void ViewCreatorDialog::onEditTextAxis2ZEnter(wxCommandEvent &event)
01558 {
01559     wxFocusEvent evt;
01560     onEditTextAxis2Z(evt);
01561 }
01562 
01563 void ViewCreatorDialog::onEditTextAxis2AngleEnter(wxCommandEvent &event)
01564 {
01565     wxFocusEvent evt;
01566     onEditTextAxis2Angle(evt);
01567 }


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