advanced_options_dialog.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 "ui_advanced_options_dialog.h" // generated by uic.
00031 
00032 #include "pr2_interactive_manipulation/advanced_options_dialog.h"
00033 #include "pr2_interactive_manipulation/interactive_manipulation_frontend.h"
00034 
00035 namespace pr2_interactive_manipulation {
00036 
00037 AdvancedOptionsDialog::AdvancedOptionsDialog(InteractiveManipulationFrontend *frontend) :
00038   QDialog( frontend ),
00039   frontend_(frontend),
00040   ui_( new Ui::AdvancedOptionsDialog ),
00041   root_nh_("")
00042 {
00043   ui_->setupUi( this );
00044   connect( ui_->reactive_grasping_box_, SIGNAL( clicked() ), this, SLOT( reactiveGraspingClicked() ));
00045   connect( ui_->reactive_transport_box_, SIGNAL( clicked() ), this, SLOT( reactiveForceClicked() ));
00046   connect( ui_->set_defaults_button_, SIGNAL( clicked() ), this, SLOT( setDefaultsClicked() ));
00047   connect( ui_->accept_button_, SIGNAL( clicked() ), this, SLOT( acceptClicked() ));
00048   connect( ui_->cancel_button_, SIGNAL( clicked() ), this, SLOT( reject() ));
00049   connect( ui_->find_alternatives_box_, SIGNAL( clicked() ), this, SLOT( findAlternativesClicked() ));
00050   connect( ui_->always_plan_grasps_box_, SIGNAL( clicked() ), this, SLOT( alwaysPlanGraspsClicked() ));
00051   connect( ui_->cycle_gripper_opening_box_, SIGNAL( clicked() ), this, SLOT( cycleGripperOpeningClicked() ));
00052 }
00053 
00054 AdvancedOptionsDialog::~AdvancedOptionsDialog()
00055 {
00056   delete ui_;
00057 }
00058 
00059 void AdvancedOptionsDialog::setDefaultsClicked()
00060 {
00061   setOptions( getDefaults() );
00062 }
00063 
00064 AdvancedGraspOptions AdvancedOptionsDialog::getDefaults(int interface_number, int task_number)
00065 {
00066   AdvancedGraspOptions go;
00067   go.reactive_grasping_ = false;
00068   go.reactive_force_ = false;
00069   go.reactive_place_ = false;
00070   go.find_alternatives_ = true;
00071   go.always_plan_grasps_ = false;
00072   go.cycle_gripper_opening_ = false;
00073   go.lift_steps_  = 10;
00074   go.retreat_steps_ = 10;
00075   go.lift_direction_choice_ = 0;
00076   go.desired_approach_ = 10;
00077   go.min_approach_ = 5;
00078   go.max_contact_force_ = 50;
00079   switch (task_number)
00080   {
00081   case 3:
00082     go.lift_direction_choice_ = 1;
00083     break;
00084   }
00085 
00086   return go;
00087 }
00088 
00089 AdvancedGraspOptions AdvancedOptionsDialog::getOptions()
00090 {
00091   AdvancedGraspOptions go;
00092   go.reactive_grasping_ = ui_->reactive_grasping_box_->isChecked();
00093   go.reactive_force_ = ui_->reactive_transport_box_->isChecked();
00094   go.reactive_place_ = ui_->reactive_place_box_->isChecked();
00095   go.find_alternatives_ = ui_->find_alternatives_box_->isChecked();
00096   go.always_plan_grasps_ = ui_->always_plan_grasps_box_->isChecked();
00097   go.cycle_gripper_opening_ = ui_->cycle_gripper_opening_box_->isChecked();
00098   go.lift_steps_  = ui_->lift_distance_spin_->value();
00099   go.retreat_steps_ = ui_->retreat_distance_spin_->value();
00100   go.lift_direction_choice_ = ui_->lift_direction_choice_->currentIndex();
00101   go.desired_approach_ = ui_->desired_grasp_approach_spin_->value();
00102   go.min_approach_ = ui_->min_grasp_approach_spin_->value();
00103   go.max_contact_force_ = ui_->max_contact_force_spin_->value();
00104   return go;
00105 }
00106 
00107 void AdvancedOptionsDialog::setOptions(AdvancedGraspOptions go)
00108 {
00109   ui_->reactive_grasping_box_->setChecked(go.reactive_grasping_);
00110   ui_->reactive_transport_box_->setChecked(go.reactive_force_);
00111   ui_->reactive_place_box_->setChecked(go.reactive_place_);
00112   ui_->find_alternatives_box_->setChecked(go.find_alternatives_);
00113   ui_->always_plan_grasps_box_->setChecked(go.always_plan_grasps_);
00114   ui_->cycle_gripper_opening_box_->setChecked(go.cycle_gripper_opening_);
00115   ui_->lift_distance_spin_->setValue(go.lift_steps_);
00116   ui_->retreat_distance_spin_->setValue(go.retreat_steps_);
00117   ui_->lift_direction_choice_->setCurrentIndex(go.lift_direction_choice_);
00118   ui_->desired_grasp_approach_spin_->setValue(go.desired_approach_);
00119   ui_->min_grasp_approach_spin_->setValue(go.min_approach_);
00120   ui_->max_contact_force_spin_->setValue(go.max_contact_force_);
00121 }
00122 
00123 void AdvancedOptionsDialog::acceptClicked()
00124 {
00125   frontend_->setAdvancedOptions(getOptionsMsg());
00126   accept();
00127 }
00128 
00129 
00130 pr2_object_manipulation_msgs::IMGUIAdvancedOptions AdvancedOptionsDialog::getDefaultsMsg(int interface_number, int task_number)
00131 {
00132   pr2_object_manipulation_msgs::IMGUIAdvancedOptions go;
00133   go.reactive_grasping = false;
00134   go.reactive_force = false;
00135   go.reactive_place = false;
00136   go.find_alternatives = true;
00137   go.always_plan_grasps = false;
00138   go.cycle_gripper_opening = false;
00139   go.lift_steps  = 10;
00140   go.retreat_steps = 10;
00141   go.lift_direction_choice = 0;
00142   go.desired_approach = 10;
00143   go.min_approach = 5;
00144   go.max_contact_force = 50;
00145   switch (task_number)
00146   {
00147   case 3:
00148     go.lift_direction_choice = 1;
00149     break;
00150   }
00151   return go;
00152 }
00153 
00154 pr2_object_manipulation_msgs::IMGUIAdvancedOptions AdvancedOptionsDialog::getOptionsMsg()
00155 {
00156   pr2_object_manipulation_msgs::IMGUIAdvancedOptions go;
00157   go.reactive_grasping = ui_->reactive_grasping_box_->isChecked();
00158   go.reactive_force = ui_->reactive_transport_box_->isChecked();
00159   go.reactive_place = ui_->reactive_place_box_->isChecked();
00160   go.find_alternatives = ui_->find_alternatives_box_->isChecked();
00161   go.always_plan_grasps = ui_->always_plan_grasps_box_->isChecked();
00162   go.cycle_gripper_opening = ui_->cycle_gripper_opening_box_->isChecked();
00163 
00164   go.lift_steps  = ui_->lift_distance_spin_->value();
00165   go.retreat_steps = ui_->retreat_distance_spin_->value();
00166   go.lift_direction_choice = ui_->lift_direction_choice_->currentIndex();
00167   go.desired_approach = ui_->desired_grasp_approach_spin_->value();
00168   go.min_approach = ui_->min_grasp_approach_spin_->value();
00169   go.max_contact_force = ui_->max_contact_force_spin_->value();
00170   return go;
00171 }
00172 
00173 void AdvancedOptionsDialog::setOptionsMsg(pr2_object_manipulation_msgs::IMGUIAdvancedOptions go)
00174 {
00175   ui_->reactive_grasping_box_->setChecked(go.reactive_grasping);
00176   ui_->reactive_transport_box_->setChecked(go.reactive_force);
00177   ui_->reactive_place_box_->setChecked(go.reactive_place);
00178   ui_->find_alternatives_box_->setChecked(go.find_alternatives);
00179   ui_->always_plan_grasps_box_->setChecked(go.always_plan_grasps);
00180   ui_->cycle_gripper_opening_box_->setChecked(go.cycle_gripper_opening);
00181   ui_->lift_distance_spin_->setValue(go.lift_steps);
00182   ui_->retreat_distance_spin_->setValue(go.retreat_steps);
00183   ui_->lift_direction_choice_->setCurrentIndex(go.lift_direction_choice);
00184   ui_->desired_grasp_approach_spin_->setValue(go.desired_approach);
00185   ui_->min_grasp_approach_spin_->setValue(go.min_approach);
00186   ui_->max_contact_force_spin_->setValue(go.max_contact_force);
00187 }
00188 
00189 void AdvancedOptionsDialog::reactiveGraspingClicked()
00190 {
00191   //reactive gripper force is only allowed together with reactive grasping
00192   if (!ui_->reactive_grasping_box_->isChecked()) ui_->reactive_transport_box_->setChecked(false);
00193 }
00194 
00195 void AdvancedOptionsDialog::reactiveForceClicked()
00196 {
00197   //reactive gripper force is only allowed together with reactive grasping
00198   if (!ui_->reactive_grasping_box_->isChecked()) ui_->reactive_grasping_box_->setChecked(true);  
00199 }
00200 
00201 void AdvancedOptionsDialog::findAlternativesClicked()
00202 {
00203   if (ui_->find_alternatives_box_->isChecked())
00204   {
00205     root_nh_.setParam("pr2_interactive_gripper_pose_action/always_find_alternatives", true);
00206   }
00207   else
00208   {
00209     root_nh_.setParam("pr2_interactive_gripper_pose_action/always_find_alternatives", false);
00210   }
00211 }
00212 
00213 void AdvancedOptionsDialog::alwaysPlanGraspsClicked()
00214 {
00215   if (ui_->always_plan_grasps_box_->isChecked())
00216   {
00217     root_nh_.setParam("pr2_interactive_gripper_pose_action/always_call_planner", true);
00218   }
00219   else
00220   {
00221     root_nh_.setParam("pr2_interactive_gripper_pose_action/always_call_planner", false);
00222   }
00223 }
00224 
00225 void AdvancedOptionsDialog::cycleGripperOpeningClicked()
00226 {
00227   if (ui_->cycle_gripper_opening_box_->isChecked())
00228   {
00229     root_nh_.setParam("pr2_interactive_gripper_pose_action/gripper_opening_cycling", true);
00230   }
00231   else
00232   {
00233     root_nh_.setParam("pr2_interactive_gripper_pose_action/gripper_opening_cycling", false);
00234   }
00235 }
00236 
00237 
00238 }


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