36 #include <wx/button.h> 39 #include <wx/msgdlg.h> 41 #include <rc_pick_client/GetRegionsOfInterest.h> 42 #include <rc_pick_client/SetRegionOfInterest.h> 43 #include <rc_pick_client/DeleteRegionsOfInterest.h> 49 : wxFrame(NULL, wxID_ANY, title, wxDefaultPosition, wxSize(500, 300))
51 nh_ = std::make_shared<ros::NodeHandle>();
56 ROS_ERROR(
"Ros parameter: /rc_roi_manager_gui/pick_module musst be set. Either rc_itempick or rc_boxpick.");
62 nh_->serviceClient<rc_pick_client::GetRegionsOfInterest>(
"/" +
pick_module_ +
"/get_regions_of_interest");
64 nh_->serviceClient<rc_pick_client::DeleteRegionsOfInterest>(
"/" +
pick_module_ +
"/delete_regions_of_interest");
69 wxPanel* panel =
new wxPanel(
this, -1);
70 item_list_ =
new wxDataViewListCtrl(panel, wxID_ANY, wxPoint(-1, -1), wxSize(-1, -1));
71 item_list_->AppendTextColumn(
"Name", wxDATAVIEW_CELL_INERT, 200, wxALIGN_LEFT,
72 wxDATAVIEW_COL_RESIZABLE | wxDATAVIEW_COL_SORTABLE);
73 item_list_->AppendTextColumn(
"Pose Frame", wxDATAVIEW_CELL_INERT, 120, wxALIGN_LEFT,
74 wxDATAVIEW_COL_RESIZABLE | wxDATAVIEW_COL_SORTABLE);
75 item_list_->AppendTextColumn(
"Shape", wxDATAVIEW_CELL_INERT, 80, wxALIGN_LEFT,
76 wxDATAVIEW_COL_RESIZABLE | wxDATAVIEW_COL_SORTABLE);
78 wxBoxSizer* vbox =
new wxBoxSizer(wxVERTICAL);
79 auto* data_box =
new wxBoxSizer(wxHORIZONTAL);
81 vbox->Add(data_box, 1, wxLEFT | wxRIGHT | wxEXPAND, 10);
83 auto* button_box =
new wxBoxSizer(wxHORIZONTAL);
84 auto* new_button =
new wxButton(panel, ID_NewButton,
"New");
85 auto* set_button =
new wxButton(panel, ID_SetButton,
"Update");
86 auto* edit_button =
new wxButton(panel, ID_EditButton,
"Edit");
87 auto* delete_button =
new wxButton(panel, ID_DeleteButton,
"Delete");
88 button_box->Add(new_button, 1);
89 button_box->Add(set_button, 1);
90 button_box->Add(edit_button, 1);
91 button_box->Add(delete_button, 1);
92 button_box->Add(-1, 0, wxEXPAND);
93 vbox->Add(button_box, 0, wxTOP | wxLEFT | wxRIGHT | wxBOTTOM, 10);
95 panel->SetSizer(vbox);
106 int selected_row =
item_list_->GetSelectedRow();
107 rc_pick_client::DeleteRegionsOfInterest srv;
108 if (selected_row != wxNOT_FOUND)
110 srv.request.region_of_interest_ids.emplace_back(
item_list_->GetTextValue(selected_row, 0));
113 ROS_ERROR(
"Unable to call the service: delete_regions_of_interest");
126 for (
int i = 0; i <
item_list_->GetItemCount(); i++)
128 auto item_name =
item_list_->GetTextValue(i, 0);
129 if (wxString(name) == item_name)
137 int selected_row =
item_list_->GetSelectedRow();
138 if (selected_row != wxNOT_FOUND)
140 rc_pick_client::GetRegionsOfInterest srv;
141 srv.request.region_of_interest_ids.emplace_back(
item_list_->GetTextValue(selected_row, 0));
150 ROS_ERROR(
"Failed to call service: get_regions_of_interest");
158 rc_pick_client::RegionOfInterest roi;
160 roi.primitive.dimensions = { 0.1, 0.1, 0.1 };
161 roi.pose.pose.orientation.w = 1;
162 roi.pose.header.frame_id =
"camera";
163 roi.primitive.type = 1;
171 rc_pick_client::GetRegionsOfInterest srv;
172 wxString shapes[] = {
"Box",
"Sphere" };
176 ROS_DEBUG(
"Size of vector of regions of interest: %zu", srv.response.regions_of_interest.size());
177 for (rc_pick_client::RegionOfInterest roi : srv.response.regions_of_interest)
179 wxVector<wxVariant> item;
180 wxString pose_frame = wxString(roi.pose.header.frame_id);
181 wxString name = wxString(roi.id);
182 wxString shape = shapes[roi.primitive.type - 1];
183 item.push_back(name);
184 item.push_back(pose_frame);
185 item.push_back(shape);
191 ROS_ERROR(
"UpdateGui: Failed to call service get_regions_of_interest");
void onDeleteButton(wxCommandEvent &)
Event handler for the delete button.
void onNewButton(wxCommandEvent &)
Event handler for the new button.
void updateGui()
Update list of shown rois on the gui.
std::shared_ptr< InteractiveRoiSelection > interactive_roi_server_
bool call(MReq &req, MRes &res)
std::shared_ptr< ros::NodeHandle > nh_
NewRoiFrame * create_roi_frame_
void onUpdateButton(wxCommandEvent &)
Event handler for the update button.
void onEditButton(wxCommandEvent &)
Event handler for the edit button.
bool isItemInList(wxString name)
Search if an roi is already present.
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ros::ServiceClient client_get_roi_
ros::ServiceClient client_delete_roi_
void setRoi(rc_pick_client::RegionOfInterest roi, bool edit)
sets the member roi_
RoiManagerFrame(const wxString &title)
Constructor.
#define ROS_INFO_STREAM(args)
wxDataViewListCtrl * item_list_