34 #include <wx/button.h> 
   37 #include <geometry_msgs/Pose.h> 
   38 #include <rc_pick_client/SetRegionOfInterest.h> 
   45   : wxFrame(NULL, wxID_ANY, title, wxDefaultPosition, wxSize(300, 280)), manager_(manager)
 
   48   nh_ = std::make_shared<ros::NodeHandle>();
 
   50       nh_->serviceClient<rc_pick_client::SetRegionOfInterest>(
"/" + pick_module + 
"/set_region_of_interest");
 
   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);
 
   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);
 
   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);
 
   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);
 
   69   vbox->Add(shape_str, 0, wxLEFT | wxTOP, 10);
 
   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);
 
   80   panel->SetSizer(vbox);
 
   97     ROS_ERROR(
"Failed to set the interactive region of interest");
 
  106     ROS_ERROR(
"Failed to get the interactive region of interest");
 
  121     wxMessageDialog* pop_up =
 
  122         new wxMessageDialog(
this, 
"A region of interest with that name already exists!", 
"Name Error");
 
  128     wxCommandEvent evt = wxCommandEvent(wxEVT_COMMAND_BUTTON_CLICKED, ID_DeleteButton);
 
  135   rc_pick_client::SetRegionOfInterest srv;
 
  136   srv.request.region_of_interest = 
roi_;
 
  139     ROS_ERROR(
"Failed to call service set_regions_of_interest");
 
  151     ROS_ERROR(
"Failed to set the interactive region of interest");