00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "pr2_interactive_manipulation/interactive_manipulation_frontend.h"
00031
00032 #include "object_manipulator/tools/camera_configurations.h"
00033
00034 #include <rviz/visualization_manager.h>
00035 #include <rviz/view_controller.h>
00036 #include <rviz/frame_manager.h>
00037 #include <OGRE/OgreMatrix3.h>
00038
00039 namespace pr2_interactive_manipulation {
00040
00041 typedef actionlib::SimpleActionClient<pr2_object_manipulation_msgs::IMGUIAction> Client;
00042
00043 InteractiveManipulationFrontend::InteractiveManipulationFrontend(wxWindow *parent,
00044 rviz::VisualizationManager* manager) :
00045 InteractiveManipulationFrameBase(parent),
00046 vis_manager_(manager),
00047 root_nh_(""),
00048 status_label_text_("idle"),
00049 adv_options_(AdvancedOptionsDialog::getDefaultsMsg())
00050 {
00051 root_nh_.param<int>("interactive_grasping/interface_number", interface_number_, 0);
00052 if (!interface_number_) ROS_WARN("No interface number specified for grasping study; using default configuration");
00053 else ROS_INFO("Using interface number %d for grasping study", interface_number_);
00054 root_nh_.param<int>("interactive_grasping/task_number", task_number_, 0);
00055 if (!task_number_) ROS_WARN("No task number specified for grasping study; using default configuration");
00056 else ROS_INFO("Using task number %d for grasping study", task_number_);
00057
00058 action_name_ = "imgui_action";
00059 action_client_ = new actionlib::SimpleActionClient<pr2_object_manipulation_msgs::IMGUIAction>(action_name_, true);
00060
00061 status_name_ = "interactive_manipulation_status";
00062 status_sub_ = root_nh_.subscribe(status_name_, 1, &InteractiveManipulationFrontend::statusCallback, this);
00063
00064 rcommander_action_info_name_ = "list_rcommander_actions";
00065 rcommander_group_name_ = "house_hold";
00066 rcommander_action_info_client_ = root_nh_.serviceClient<pr2_object_manipulation_msgs::ActionInfo>(rcommander_action_info_name_);
00067 rcommanderRefresh();
00068
00069
00070
00071
00072 collision_panel_->Enable(false);
00073 helper_panel_->Enable(false);
00074 actions_panel_->Enable(false);
00075 place_button_->Enable(false);
00076 stop_nav_button_->Enable(true);
00077
00078 advanced_options_button_->Enable(false);
00079 adv_options_ = AdvancedOptionsDialog::getDefaultsMsg(interface_number_, task_number_);
00080
00081 switch (interface_number_)
00082 {
00083 case 1:
00084 collision_box_->SetValue(false);
00085 grasp_button_->Enable(false);
00086 planned_move_button_->Enable(false);
00087 break;
00088 case 2:
00089 collision_box_->SetValue(false);
00090 grasp_button_->Enable(false);
00091 planned_move_button_->Enable(true);
00092 break;
00093 case 3:
00094 grasp_button_->Enable(true);
00095 planned_move_button_->Enable(false);
00096 break;
00097 case 4:
00098 grasp_button_->Enable(true);
00099 planned_move_button_->Enable(false);
00100 break;
00101 case 0:
00102 collision_panel_->Enable(true);
00103 helper_panel_->Enable(true);
00104 actions_panel_->Enable(true);
00105 place_button_->Enable(true);
00106 advanced_options_button_->Enable(true);
00107 }
00108 grasp_place_panel_->SetFocus();
00109 }
00110
00111 InteractiveManipulationFrontend::~InteractiveManipulationFrontend()
00112 {
00113 delete action_client_;
00114 }
00115
00116 wxString getWxString(std::string str)
00117 {
00118 wxString mystring(str.c_str(), wxConvUTF8);
00119 return mystring;
00120 }
00121
00122 void InteractiveManipulationFrontend::update()
00123 {
00124 status_label_mutex_.lock();
00125 wxString mystring(status_label_text_.c_str(), wxConvUTF8);
00126 status_label_mutex_.unlock();
00127 status_label_->SetLabel(mystring);
00128
00129 reset_button_->Enable(collision_box_->IsChecked());
00130 reset_choice_->Enable(collision_box_->IsChecked());
00131 }
00132
00133 void InteractiveManipulationFrontend::statusCallback( const std_msgs::StringConstPtr &status)
00134 {
00135 ROS_DEBUG_STREAM("IM Frontend received stauts: " << status->data);
00136 boost::mutex::scoped_lock lock(status_label_mutex_);
00137 status_label_text_ = status->data;
00138 }
00139
00140 void InteractiveManipulationFrontend::feedbackCallback(const pr2_object_manipulation_msgs::IMGUIFeedbackConstPtr &feedback)
00141 {
00142
00143
00144
00145
00146
00147
00148 }
00149
00150 void InteractiveManipulationFrontend::cancelButtonClicked( wxCommandEvent& )
00151 {
00152 action_client_->cancelAllGoals();
00153 }
00154
00155 void InteractiveManipulationFrontend::stopNavButtonClicked( wxCommandEvent& )
00156 {
00157 pr2_object_manipulation_msgs::IMGUIGoal goal;
00158 goal.options = getDialogOptions();
00159 goal.command.command = goal.command.STOP_NAV;
00160 action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00161 boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00162 }
00163
00164 void InteractiveManipulationFrontend::graspButtonClicked( wxCommandEvent& )
00165 {
00166 pr2_object_manipulation_msgs::IMGUIGoal goal;
00167 goal.options = getDialogOptions();
00168 goal.command.command = goal.command.PICKUP;
00169 action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00170 boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00171 }
00172
00173 void InteractiveManipulationFrontend::placeButtonClicked( wxCommandEvent& )
00174 {
00175 pr2_object_manipulation_msgs::IMGUIGoal goal;
00176 goal.options = getDialogOptions();
00177 goal.command.command = goal.command.PLACE;
00178 action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00179 boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00180 }
00181
00182 void InteractiveManipulationFrontend::plannedMoveButtonClicked( wxCommandEvent& )
00183 {
00184 pr2_object_manipulation_msgs::IMGUIGoal goal;
00185 goal.options = getDialogOptions();
00186 goal.command.command = goal.command.PLANNED_MOVE;
00187 action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00188 boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00189 }
00190
00191 void InteractiveManipulationFrontend::resetButtonClicked( wxCommandEvent& )
00192 {
00193 pr2_object_manipulation_msgs::IMGUIGoal goal;
00194 goal.options = getDialogOptions();
00195 goal.command.command = goal.command.RESET;
00196 action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00197 boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00198 }
00199
00200 void InteractiveManipulationFrontend::armGoButtonClicked( wxCommandEvent& )
00201 {
00202 pr2_object_manipulation_msgs::IMGUIGoal goal;
00203 goal.options = getDialogOptions();
00204 goal.command.command = goal.command.MOVE_ARM;
00205 action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00206 boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00207 }
00208
00209 void InteractiveManipulationFrontend::modelObjectClicked( wxCommandEvent& )
00210 {
00211 pr2_object_manipulation_msgs::IMGUIGoal goal;
00212 goal.options = getDialogOptions();
00213 goal.command.command = goal.command.MODEL_OBJECT;
00214 action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00215 boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00216 }
00217
00218
00219
00220
00221
00222
00223
00224
00225
00226
00227 void InteractiveManipulationFrontend::rcommandRunButtonClicked( wxCommandEvent& event)
00228 {
00229
00230 int selection;
00231 pr2_object_manipulation_msgs::IMGUIGoal goal;
00232 selection = rcommander_choice->GetSelection();
00233 if (selection == -1)
00234 return;
00235
00236 goal.options = getDialogOptions();
00237 goal.command.command = goal.command.SCRIPTED_ACTION;
00238 goal.command.script_name = std::string(rcommander_choice->GetString(selection).mb_str());
00239 goal.command.script_group_name = rcommander_group_name_;
00240 action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00241 boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00242 }
00243
00244 void InteractiveManipulationFrontend::rcommandRefreshButtonClicked( wxCommandEvent& event)
00245 {
00246 rcommanderRefresh();
00247 }
00248
00249 void InteractiveManipulationFrontend::rcommanderRefresh()
00250 {
00251
00252 pr2_object_manipulation_msgs::ActionInfo srv;
00253 srv.request.group_name = rcommander_group_name_;
00254 if (rcommander_action_info_client_.call(srv))
00255 {
00256 rcommander_choice->Clear();
00257 for (unsigned int i = 0; i < srv.response.services.size(); i++)
00258 {
00259 rcommander_choice->Append(getWxString(srv.response.services[i]));
00260
00261 }
00262 rcommander_choice->SetSelection( 0 );
00263 }
00264 }
00265
00266
00267 void InteractiveManipulationFrontend::gripperSliderScrollChanged( wxScrollEvent& )
00268 {
00269 pr2_object_manipulation_msgs::IMGUIGoal goal;
00270 goal.options = getDialogOptions();
00271 goal.command.command = goal.command.MOVE_GRIPPER;
00272 action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00273 boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00274 }
00275
00276 void InteractiveManipulationFrontend::advancedOptionsClicked( wxCommandEvent& )
00277 {
00278 AdvancedOptionsDialog *dlg = new AdvancedOptionsDialog(this);
00279 dlg->setOptionsMsg(adv_options_);
00280 dlg->Show();
00281 }
00282
00283 pr2_object_manipulation_msgs::IMGUIOptions InteractiveManipulationFrontend::getDialogOptions()
00284 {
00285 pr2_object_manipulation_msgs::IMGUIOptions options;
00286 options.collision_checked = collision_box_->IsChecked();
00287 options.grasp_selection = 0;
00288 options.arm_selection = arm_choice_->GetSelection();
00289 options.reset_choice = reset_choice_->GetSelection();
00290 options.arm_action_choice = arm_action_choice_->GetSelection();
00291 options.arm_planner_choice = arm_planner_choice_->GetSelection();
00292 options.adv_options = adv_options_;
00293 options.gripper_slider_position = gripper_slider_->GetValue();
00294 return options;
00295 }
00296
00297
00298
00299
00300
00301 void InteractiveManipulationFrontend::setCamera(std::vector<double> params)
00302 {
00303 float yaw_correction = 0;
00304 Ogre::Vector3 pos;
00305 Ogre::Quaternion orient;
00306
00307
00308 if (rviz::FrameManager::instance()->getTransform("base_link",
00309 ros::Time(), pos, orient) )
00310 {
00311 yaw_correction = orient.getRoll().valueRadians();
00312 }
00313 params[1] -= yaw_correction;
00314
00315
00316 Ogre::Vector3 focal_point(params[3], params[4], params[5]);
00317 Ogre::Matrix3 rot;
00318 rot.FromAxisAngle(Ogre::Vector3(0,1,0), Ogre::Radian(yaw_correction));
00319 focal_point = rot * focal_point;
00320 for(int i=0; i<3; i++) params[3+i] = focal_point[i];
00321
00322
00323 std::ostringstream os;
00324 for(int i=0; i<6; i++) os << params[i] << ' ';
00325 std::string s(os.str());
00326 vis_manager_->setTargetFrame("base_link");
00327 vis_manager_->setCurrentViewControllerType( "Orbit" );
00328 rviz::ViewController* vc = vis_manager_->getCurrentViewController();
00329 vc->fromString(s);
00330 vis_manager_->queueRender();
00331 }
00332
00333 void InteractiveManipulationFrontend::cameraLeftButtonClicked( wxCommandEvent& event )
00334 {
00335 setCamera( object_manipulator::cameraConfigurations().get_camera_pose("left") );
00336 }
00337
00338 void InteractiveManipulationFrontend::cameraRightButtonClicked( wxCommandEvent& event )
00339 {
00340 setCamera( object_manipulator::cameraConfigurations().get_camera_pose("right") );
00341 }
00342
00343 void InteractiveManipulationFrontend::cameraFrontButtonClicked( wxCommandEvent& event )
00344 {
00345 setCamera( object_manipulator::cameraConfigurations().get_camera_pose("front") );
00346 }
00347
00348 void InteractiveManipulationFrontend::cameraTopButtonClicked( wxCommandEvent& event )
00349 {
00350 setCamera( object_manipulator::cameraConfigurations().get_camera_pose("top") );
00351 }
00352
00353 }