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