new_roi_frame.cc
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Roboception GmbH
3  *
4  * Author: Carlos Xavier Garcia Briones
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright notice,
10  * this list of conditions and the following disclaimer.
11  *
12  * 2. Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its contributors
17  * may be used to endorse or promote products derived from this software without
18  * specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
23  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
24  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
25  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
26  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
27  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
28  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
29  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #include "new_roi_frame.h"
34 #include <wx/button.h>
35 #include <wx/panel.h>
36 #include <wx/sizer.h>
37 #include <geometry_msgs/Pose.h>
38 #include <rc_pick_client/SetRegionOfInterest.h>
39 
40 #include "event_ids.h"
41 
42 namespace rc_roi_manager_gui
43 {
44 NewRoiFrame::NewRoiFrame(const wxString& title, RoiManagerFrame* manager, std::string pick_module)
45  : wxFrame(NULL, wxID_ANY, title, wxDefaultPosition, wxSize(300, 280)), manager_(manager)
46 {
47  manager_->Show(false);
48  nh_ = std::make_shared<ros::NodeHandle>();
50  nh_->serviceClient<rc_pick_client::SetRegionOfInterest>("/" + pick_module + "/set_region_of_interest");
51 
52  wxPanel* panel = new wxPanel(this, -1);
53  auto name_str = new wxStaticText(panel, wxID_ANY, wxT("Roi Name"));
54  name_box_ = new wxTextCtrl(panel, wxID_ANY);
55 
56  auto pose_frame_str = new wxStaticText(panel, wxID_ANY, wxT("Pose Frame"));
57  wxString pose_frame_choices[] = { "camera", "external" };
58  pose_frame_box_ = new wxChoice(panel, wxID_ANY, wxDefaultPosition, wxDefaultSize, 2, pose_frame_choices);
59 
60  auto shape_str = new wxStaticText(panel, wxID_ANY, wxT("Shape"));
61  wxString shape_choices[] = { "box", "sphere" };
62  shape_box_ = new wxChoice(panel, wxID_ANY, wxDefaultPosition, wxDefaultSize, 2, shape_choices);
63 
64  auto* vbox = new wxBoxSizer(wxVERTICAL);
65  vbox->Add(name_str, 0, wxLEFT | wxRIGHT | wxTOP, 10);
66  vbox->Add(name_box_, 0, wxEXPAND | wxLEFT | wxRIGHT | wxTOP, 10);
67  vbox->Add(pose_frame_str, 0, wxLEFT | wxTOP, 10);
68  vbox->Add(pose_frame_box_, 0, wxLEFT | wxTOP, 10);
69  vbox->Add(shape_str, 0, wxLEFT | wxTOP, 10);
70  vbox->Add(shape_box_, 0, wxLEFT | wxTOP, 10);
71 
72  wxButton* btn1 = new wxButton(panel, ID_SaveButton, wxT("Save"));
73  wxButton* btn2 = new wxButton(panel, ID_UpdateRoiButton, wxT("Update"));
74  wxButton* btn3 = new wxButton(panel, ID_CancelButton, wxT("Cancel"));
75  auto* hbox = new wxBoxSizer(wxHORIZONTAL);
76  hbox->Add(btn1, 0, wxLEFT | wxTOP, 10);
77  hbox->Add(btn2, 0, wxLEFT | wxTOP, 10);
78  hbox->Add(btn3, 0, wxLEFT | wxTOP, 10);
79  vbox->Add(hbox);
80  panel->SetSizer(vbox);
81 
82  CenterOnParent();
83  Connect(ID_SaveButton, wxEVT_COMMAND_BUTTON_CLICKED, wxCommandEventHandler(NewRoiFrame::onSaveButton));
84  Connect(ID_CancelButton, wxEVT_COMMAND_BUTTON_CLICKED, wxCommandEventHandler(NewRoiFrame::onCancelButton));
85  Connect(ID_UpdateRoiButton, wxEVT_COMMAND_BUTTON_CLICKED, wxCommandEventHandler(NewRoiFrame::onUpdateButton));
86 }
87 
88 void NewRoiFrame::setRoi(rc_pick_client::RegionOfInterest roi, bool edit)
89 {
90  is_editing_ = edit;
91  roi_ = roi;
92  name_box_->AppendText(roi_.id);
93  shape_box_->SetSelection(roi_.primitive.type - 1);
94  pose_frame_box_->SetStringSelection(roi_.pose.header.frame_id);
95  if (!manager_->interactive_roi_server_->setInteractiveRoi(roi_))
96  {
97  ROS_ERROR("Failed to set the interactive region of interest");
98  }
99 }
100 
101 // TODO get suggests that you are getting something in return. What is this function doing?
103 {
104  if (!manager_->interactive_roi_server_->getInteractiveRoi(roi_))
105  {
106  ROS_ERROR("Failed to get the interactive region of interest");
107  }
108 }
109 
110 void NewRoiFrame::onCancelButton(wxCommandEvent&)
111 {
112  this->Close();
113 }
114 
115 void NewRoiFrame::onSaveButton(wxCommandEvent&)
116 {
118 
119  if (manager_->isItemInList(name_box_->GetValue()) && (roi_.id != name_box_->GetValue()))
120  {
121  wxMessageDialog* pop_up =
122  new wxMessageDialog(this, "A region of interest with that name already exists!", "Name Error");
123  pop_up->ShowModal();
124  return;
125  }
126  if (is_editing_)
127  {
128  wxCommandEvent evt = wxCommandEvent(wxEVT_COMMAND_BUTTON_CLICKED, ID_DeleteButton);
129  manager_->onDeleteButton(evt);
130  }
131 
132  roi_.id = name_box_->GetValue();
133  roi_.pose.header.frame_id = pose_frame_box_->GetStringSelection();
134  roi_.primitive.type = shape_box_->GetSelection() + 1;
135  rc_pick_client::SetRegionOfInterest srv;
136  srv.request.region_of_interest = roi_;
137  if (!client_set_roi_.call(srv))
138  {
139  ROS_ERROR("Failed to call service set_regions_of_interest");
140  }
141  this->Close();
142 }
143 
144 void NewRoiFrame::onUpdateButton(wxCommandEvent&)
145 {
147  roi_.pose.header.frame_id = pose_frame_box_->GetStringSelection();
148  roi_.primitive.type = shape_box_->GetSelection() + 1;
149  if (!manager_->interactive_roi_server_->setInteractiveRoi(roi_))
150  {
151  ROS_ERROR("Failed to set the interactive region of interest");
152  }
153 }
154 
156 {
157  manager_->updateGui();
159  manager_->Show(true);
160 }
161 
162 } // namespace rc_roi_manager_gui
void onDeleteButton(wxCommandEvent &)
Event handler for the delete button.
void updateGui()
Update list of shown rois on the gui.
rc_pick_client::RegionOfInterest roi_
Definition: new_roi_frame.h:92
std::shared_ptr< InteractiveRoiSelection > interactive_roi_server_
std::shared_ptr< ros::NodeHandle > nh_
Definition: new_roi_frame.h:93
bool call(MReq &req, MRes &res)
bool isItemInList(wxString name)
Search if an roi is already present.
ros::ServiceClient client_set_roi_
Definition: new_roi_frame.h:94
NewRoiFrame(const wxString &title, RoiManagerFrame *manager, std::string pick_module)
Constructor.
void onCancelButton(wxCommandEvent &)
Event handler for the cancel button.
void setRoi(rc_pick_client::RegionOfInterest roi, bool edit)
sets the member roi_
void onUpdateButton(wxCommandEvent &)
Event handler for the update button.
void onSaveButton(wxCommandEvent &)
Event handler for the save button.
void setFromInteractiveRoi()
Ros service that sets the region of interest from roi in interactive_roi_selection server...
#define ROS_ERROR(...)


rc_roi_manager_gui
Author(s): Carlos Xavier Garcia Briones
autogenerated on Sat Feb 13 2021 03:42:01