interactive_manipulation_frontend.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "pr2_interactive_manipulation/interactive_manipulation_frontend.h"
00031 
00032 #include "object_manipulator/tools/camera_configurations.h"
00033 
00034 #include <rviz/display_context.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" // generated by uic from interactive_manipulation.ui
00040 
00041 namespace pr2_interactive_manipulation {
00042 
00043 typedef actionlib::SimpleActionClient<pr2_object_manipulation_msgs::IMGUIAction> Client;
00044 
00045 InteractiveManipulationFrontend::InteractiveManipulationFrontend(rviz::DisplayContext* context, QWidget* parent) : 
00046   QWidget( parent ),
00047   context_(context),
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   power_name_ = "power_state";
00084   power_sub_ = root_nh_.subscribe(power_name_, 1, &InteractiveManipulationFrontend::powerCallback, this);
00085   
00086   draw_reachable_zones_pub_ = root_nh_.advertise<std_msgs::Empty>("/draw_reachable_zones/ping", 10);
00087 
00088   rcommander_action_info_name_ = "list_rcommander_actions";
00089   rcommander_group_name_ = "house_hold";
00090   rcommander_action_info_client_ = root_nh_.serviceClient<pr2_object_manipulation_msgs::ActionInfo>(rcommander_action_info_name_);
00091 
00092   //scripted_action_name_ = "run_rcommander_action";
00093   //scripted_action_client_ = new actionlib::SimpleActionClient<RunScriptAction>(scripted_action_name, true);
00094 
00095   ui_->collision_panel_->setEnabled(false);
00096   ui_->helper_panel_->setEnabled(false);
00097   ui_->actions_panel_->setEnabled(false);
00098   ui_->place_button_->setEnabled(false);
00099   ui_->stop_nav_button_->setEnabled(true);
00100 
00101   ui_->advanced_options_button_->setEnabled(false);
00102   adv_options_ = AdvancedOptionsDialog::getDefaultsMsg(interface_number_, task_number_);
00103 
00104   switch (interface_number_)
00105   {
00106   case 1:
00107     ui_->collision_box_->setChecked(false);
00108     ui_->grasp_button_->setEnabled(false);
00109     ui_->planned_move_button_->setEnabled(false);
00110     break;
00111   case 2:
00112     ui_->collision_box_->setChecked(false);
00113     ui_->grasp_button_->setEnabled(false);
00114     ui_->planned_move_button_->setEnabled(true);
00115     break;
00116   case 3:
00117     ui_->grasp_button_->setEnabled(true);
00118     ui_->planned_move_button_->setEnabled(false);
00119     break;
00120   case 4:
00121     ui_->grasp_button_->setEnabled(true);
00122     ui_->planned_move_button_->setEnabled(false);
00123     break;
00124   case 0:
00125     ui_->collision_panel_->setEnabled(true);
00126     ui_->helper_panel_->setEnabled(true);
00127     ui_->actions_panel_->setEnabled(true);
00128     ui_->place_button_->setEnabled(true);
00129     ui_->advanced_options_button_->setEnabled(true);
00130     break;
00131   } 
00132   ui_->grasp_place_panel_->setFocus();
00133 }
00134 
00135 InteractiveManipulationFrontend::~InteractiveManipulationFrontend()
00136 {
00137   delete action_client_;
00138 }
00139 
00140 void InteractiveManipulationFrontend::update()
00141 {
00142   status_label_mutex_.lock();
00143   QString mystring = QString::fromUtf8( status_label_text_.c_str() );
00144   status_label_mutex_.unlock();
00145   ui_->status_label_->setText(mystring);
00146 
00147   power_label_mutex_.lock();
00148   mystring = QString::fromUtf8( power_label_text_.c_str() );
00149   power_label_mutex_.unlock();
00150   ui_->power_label_->setText(mystring);
00151 
00152   ui_->reset_button_->setEnabled(ui_->collision_box_->isChecked());
00153   ui_->reset_choice_->setEnabled(ui_->collision_box_->isChecked());
00154 }
00155 
00156 void InteractiveManipulationFrontend::statusCallback( const std_msgs::StringConstPtr &status)
00157 {
00158   ROS_DEBUG_STREAM("IM Frontend received stauts: " << status->data);
00159   boost::mutex::scoped_lock lock(status_label_mutex_);
00160   status_label_text_ = status->data;
00161 }
00162 
00163 void InteractiveManipulationFrontend::powerCallback( const pr2_msgs::PowerStateConstPtr &power)
00164 {
00165   std::ostringstream numstr;
00166   numstr << (int)power->relative_capacity << "%";
00167   boost::mutex::scoped_lock lock(power_label_mutex_);
00168   power_label_text_ = numstr.str();
00169 }
00170 
00171 void InteractiveManipulationFrontend::feedbackCallback(const pr2_object_manipulation_msgs::IMGUIFeedbackConstPtr &feedback)
00172 {
00173   //we are now doing this with topic subscription instead
00174   /*
00175   ROS_DEBUG_STREAM("IM Frontend received feedback" << feedback->status);
00176   boost::mutex::scoped_lock lock(status_label_mutex_);
00177   status_label_text_ = feedback->status;
00178   */  
00179 }
00180 
00181 void InteractiveManipulationFrontend::cancelButtonClicked()
00182 {
00183   action_client_->cancelAllGoals();
00184 }
00185 
00186 void InteractiveManipulationFrontend::stopNavButtonClicked()
00187 {
00188   pr2_object_manipulation_msgs::IMGUIGoal goal;
00189   goal.options = getDialogOptions();
00190   goal.command.command = goal.command.STOP_NAV;
00191   action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00192                            boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00193 }
00194 
00195 void InteractiveManipulationFrontend::centerHeadButtonClicked()
00196 {
00197   pr2_object_manipulation_msgs::IMGUIGoal goal;
00198   goal.options = getDialogOptions();
00199   goal.command.command = goal.command.LOOK_AT_TABLE;
00200   action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00201                            boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00202 }
00203 
00204 void InteractiveManipulationFrontend::drawReachableZonesButtonClicked()
00205 {
00206   draw_reachable_zones_pub_.publish(std_msgs::Empty());
00207 }
00208 
00209 void InteractiveManipulationFrontend::graspButtonClicked()
00210 {
00211   pr2_object_manipulation_msgs::IMGUIGoal goal;
00212   goal.options = getDialogOptions();
00213   goal.command.command = goal.command.PICKUP;
00214   action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00215                            boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00216 }
00217 
00218 void InteractiveManipulationFrontend::placeButtonClicked()
00219 {
00220   pr2_object_manipulation_msgs::IMGUIGoal goal;
00221   goal.options = getDialogOptions();
00222   goal.command.command = goal.command.PLACE;
00223   action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00224                            boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00225 }
00226 
00227 void InteractiveManipulationFrontend::plannedMoveButtonClicked()
00228 {
00229   pr2_object_manipulation_msgs::IMGUIGoal goal;
00230   goal.options = getDialogOptions();
00231   goal.command.command = goal.command.PLANNED_MOVE;
00232   action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00233                            boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00234 }
00235 
00236 void InteractiveManipulationFrontend::resetButtonClicked()
00237 {
00238   pr2_object_manipulation_msgs::IMGUIGoal goal;
00239   goal.options = getDialogOptions();
00240   goal.command.command = goal.command.RESET;  
00241   action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00242                            boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00243 }
00244 
00245 void InteractiveManipulationFrontend::armGoButtonClicked()
00246 {
00247   pr2_object_manipulation_msgs::IMGUIGoal goal;
00248   goal.options = getDialogOptions();
00249   goal.command.command = goal.command.MOVE_ARM;
00250   action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00251                            boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00252 }
00253 
00254 void InteractiveManipulationFrontend::modelObjectClicked()
00255 {
00256   pr2_object_manipulation_msgs::IMGUIGoal goal;
00257   goal.options = getDialogOptions();
00258   goal.command.command = goal.command.MODEL_OBJECT;
00259   action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00260                            boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00261 }
00262 
00263 //void InteractiveManipulationFrontend::openDrawerButtonClicked()
00264 //{
00265 //  IMGUIGoal goal;
00266 //  goal.options = getDialogOptions();
00267 //  goal.command.command = goal.command.OPEN_DRAWER;
00268 //  action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00269 //                           boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00270 //}
00271 
00272 void InteractiveManipulationFrontend::rcommandRunButtonClicked()
00273 {
00274     //Call RunScriptAction
00275     pr2_object_manipulation_msgs::IMGUIGoal goal;
00276 
00277     goal.options = getDialogOptions();
00278     goal.command.command = goal.command.SCRIPTED_ACTION;
00279     goal.command.script_name = ui_->rcommander_choice_->currentText().toStdString();
00280     if( goal.command.script_name == "" )
00281       return;
00282     goal.command.script_group_name = rcommander_group_name_;
00283     action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00284                              boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00285 }
00286 
00287 void InteractiveManipulationFrontend::rcommandRefreshButtonClicked()
00288 {
00289     //Call service for list of actions
00290     pr2_object_manipulation_msgs::ActionInfo srv;
00291     srv.request.group_name = rcommander_group_name_;
00292     if (rcommander_action_info_client_.call(srv))
00293     {
00294         ui_->rcommander_choice_->clear();
00295         for (unsigned int i = 0; i < srv.response.services.size(); i++)
00296         {
00297           ui_->rcommander_choice_->addItem( QString::fromUtf8( srv.response.services[i].c_str() ));
00298         }
00299     }
00300 }
00301 
00302 void InteractiveManipulationFrontend::gripperSliderScrollChanged()
00303 {
00304   pr2_object_manipulation_msgs::IMGUIGoal goal;
00305   goal.options = getDialogOptions();
00306   goal.command.command = goal.command.MOVE_GRIPPER;
00307   action_client_->sendGoal(goal,Client::SimpleDoneCallback(), Client::SimpleActiveCallback(),
00308                            boost::bind(&InteractiveManipulationFrontend::feedbackCallback, this, _1));
00309 }
00310 
00311 void InteractiveManipulationFrontend::advancedOptionsClicked()
00312 {
00313   AdvancedOptionsDialog *dlg = new AdvancedOptionsDialog(this);
00314   dlg->setOptionsMsg(adv_options_);
00315   dlg->show();
00316 }
00317 
00318 pr2_object_manipulation_msgs::IMGUIOptions InteractiveManipulationFrontend::getDialogOptions()
00319 {
00320   pr2_object_manipulation_msgs::IMGUIOptions options;
00321   options.collision_checked = ui_->collision_box_->isChecked();
00322   options.grasp_selection = 0;
00323   options.arm_selection = ui_->arm_choice_->currentIndex();
00324   options.reset_choice = ui_->reset_choice_->currentIndex();
00325   options.arm_action_choice = ui_->arm_action_choice_->currentIndex();
00326   options.arm_planner_choice = ui_->arm_planner_choice_->currentIndex();
00327   options.adv_options = adv_options_;
00328   options.gripper_slider_position = ui_->gripper_slider_->value();
00329   return options;
00330 }
00331 
00332 void InteractiveManipulationFrontend::setCamera(std::vector<double> params)
00333 {
00334   ROS_ERROR( "setCamera is not supported anymore." );
00335 #if 0
00336   float yaw_correction = 0;
00337   Ogre::Vector3 pos;
00338   Ogre::Quaternion orient;
00339 
00340   //correct for yaw rotation
00341   if (context_->getFrameManager()->getTransform("base_link",
00342                                                     ros::Time(),  pos, orient) )
00343   {
00344     yaw_correction = orient.getRoll().valueRadians();
00345   }
00346   params[1] -= yaw_correction;
00347 
00348   //also need to rotate the focal point
00349   Ogre::Vector3 focal_point(params[3], params[4], params[5]);
00350   Ogre::Matrix3 rot;
00351   rot.FromAxisAngle(Ogre::Vector3(0,1,0), Ogre::Radian(yaw_correction));
00352   focal_point = rot * focal_point;
00353   for(int i=0; i<3; i++) params[3+i] = focal_point[i];
00354 
00355   //set the camera params
00356   std::ostringstream os;
00357   for(int i=0; i<6; i++) os << params[i] << ' ';
00358   std::string s(os.str());
00359   //context_->setTargetFrame("base_link");
00360   //context_->setCurrentViewControllerType( "Orbit" );
00361   rviz::ViewController* vc = context_->getCurrentViewController();
00362   vc->fromString(s);
00363   context_->queueRender();
00364 #endif
00365 }
00366 
00367 void InteractiveManipulationFrontend::cameraLeftButtonClicked()
00368 {
00369   setCamera( object_manipulator::cameraConfigurations().get_camera_pose("left") );
00370 }
00371 
00372 void InteractiveManipulationFrontend::cameraRightButtonClicked()
00373 {
00374   setCamera( object_manipulator::cameraConfigurations().get_camera_pose("right") );
00375 }
00376 
00377 void InteractiveManipulationFrontend::cameraFrontButtonClicked()
00378 {
00379   setCamera( object_manipulator::cameraConfigurations().get_camera_pose("front") );
00380 }
00381 
00382 void InteractiveManipulationFrontend::cameraTopButtonClicked()
00383 {
00384   setCamera( object_manipulator::cameraConfigurations().get_camera_pose("top") );
00385 }
00386 
00387 }


pr2_interactive_manipulation_frontend
Author(s): Jonathan Binney
autogenerated on Mon Oct 6 2014 12:06:28