31 from __future__ 
import division
    37 from python_qt_binding 
import loadUi
    38 from python_qt_binding.QtCore 
import Qt, QTimer, Slot, QBasicTimer, Signal
    39 from python_qt_binding.QtWidgets 
import QWidget, QMessageBox
    40 from python_qt_binding.QtGui 
import QPixmap
    46 from bhand_controller.msg 
import State, TactileArray, Service
    47 from bhand_controller.srv 
import Actions, SetControlMode
    48 from sensor_msgs.msg 
import JointState
    49 from rospy.exceptions 
import ROSException
    52 max_base_spread = 3.14
    53 max_finger_spread = 2.44
    56 BHAND_VELOCITY_COMMANDS_FREQ = 50 
    61                 super(BHandGUI, self).
__init__(context)
    62                 self.setObjectName(
'BHandGUI')
   107                 ui_file = os.path.join(rp.get_path(
'rqt_bhand'), 
'resource', 
'BHandGUI.ui')
   109                 self._widget.setObjectName(
'BHandGUI')
   111                 pixmap_red_file = os.path.join(rp.get_path(
'rqt_bhand'), 
'resource', 
'red.png')
   112                 pixmap_green_file = os.path.join(rp.get_path(
'rqt_bhand'), 
'resource', 
'green.png')
   115                 self._widget.qlabel_state_connection.setPixmap(self.
_pixmap_red) 
   116                 self._widget.qlabel_jointstate_connection.setPixmap(self.
_pixmap_red) 
   119                 if context.serial_number() > 1:
   120                         self._widget.setWindowTitle(self._widget.windowTitle() + (
' (%d)' % context.serial_number()))           
   123                 context.add_widget(self.
_widget)
   147                         self._joint_data.position.append(0.0)
   148                         self._joint_data.velocity.append(0.0)
   149                         self._joint_data.effort.append(0.0)
   154                 except ValueError, e:
   155                         rospy.logerr(
'BHandGUI: Error connecting topic (%s)'%e)
   159                 except ValueError, e:
   160                         rospy.logerr(
'BHandGUI: Error connecting topic (%s)'%e)
   164                 except ValueError, e:
   165                         rospy.logerr(
'BHandGUI: Error connecting topic (%s)'%e)
   170                 except ROSException, e:
   171                         rospy.logerr(
'BHandGUI: Error creating publisher for topic %s (%s)'%(self.
_command_topic, e))
   176                 except ValueError, e:
   177                         rospy.logerr(
'BHandGUI: Error connecting service (%s)'%e)
   181                 except ValueError, e:
   182                         rospy.logerr(
'BHandGUI: Error connecting service (%s)'%e)
   191                 self._widget.pushButton_stop.clicked.connect(self.
stop)
   209                 self._widget.checkBox_enable_control_vel.setChecked(
False)
   225                         Read ROS params from server   227                 _name = rospy.get_name()
   231                 self.
joint_ids  = rospy.get_param(
'%s/joint_ids'%(self.
bhand_node_name), [
'F1', 
'F1_TIP', 
'F2', 
'F2_TIP', 
'F3', 
'F3_TIP', 
'SPREAD_1', 
'SPREAD_2'])
   232                 self.
joint_names  = rospy.get_param(
'%s/joint_names'%(self.
bhand_node_name), [
'bh_j12_joint', 
'bh_j13_joint', 
'bh_j22_joint', 
'bh_j23_joint', 
'bh_j32_joint', 
'bh_j31_joint', 
'bh_j11_joint', 
'bh_j21_joint'])
   234                 rospy.loginfo(
'%s::read_ros_params: bhand_node_name = %s'%(_name, self.
bhand_node_name))
   235                 rospy.loginfo(
'%s::read_ros_params: joint_ids = %s'%(_name, self.
joint_ids))
   236                 rospy.loginfo(
'%s::read_ros_params: joint_names = %s'%(_name, self.
joint_names))
   254                 self._timer.start(1, self)
   262                         Handles the press button event to call initialization service   266                         rospy.wait_for_service(self._actions_service_name)   268                                 action = rospy.ServiceProxy(self._actions_service_name, Actions)   269                                 resp1 = action(Service.INIT_HAND)   271                         except rospy.ServiceException, e:   272                                 rospy.logerr("Service call failed: %s"%e)   277                         Handles the press button event to call close hand service   280                 self._widget.radioButtonPosition.setChecked(
True)
   286                         Handles the press button event to call open hand service   293                         Handles the press button event to call set mode 1  service   300                         Handles the press button event to call set mode 2 service   317                         self._widget.horizontalSlider_3.setSliderPosition(self._widget.horizontalSlider_2.value())
   318                         self._widget.horizontalSlider_4.setSliderPosition(self._widget.horizontalSlider_2.value())
   326                         self._widget.horizontalSlider_2.setSliderPosition(self._widget.horizontalSlider_3.value())
   327                         self._widget.horizontalSlider_4.setSliderPosition(self._widget.horizontalSlider_3.value())
   335                         self._widget.horizontalSlider_2.setSliderPosition(self._widget.horizontalSlider_4.value())
   336                         self._widget.horizontalSlider_3.setSliderPosition(self._widget.horizontalSlider_4.value())
   342                         Handler for slider v_spread   349                         Handler for slider v_f1   352                 if self._widget.checkBox_moveall_velocity.isChecked():
   353                         self._widget.horizontalSlider_v_f2.setSliderPosition(self._widget.horizontalSlider_v_f1.value())
   354                         self._widget.horizontalSlider_v_f3.setSliderPosition(self._widget.horizontalSlider_v_f1.value())
   359                         Handler for slider v_f2   362                 if self._widget.checkBox_moveall_velocity.isChecked():
   363                         self._widget.horizontalSlider_v_f1.setSliderPosition(self._widget.horizontalSlider_v_f2.value())
   364                         self._widget.horizontalSlider_v_f3.setSliderPosition(self._widget.horizontalSlider_v_f2.value())
   369                         Handler for slider v_f3   372                 if self._widget.checkBox_moveall_velocity.isChecked():
   373                         self._widget.horizontalSlider_v_f2.setSliderPosition(self._widget.horizontalSlider_v_f3.value())
   374                         self._widget.horizontalSlider_v_f1.setSliderPosition(self._widget.horizontalSlider_v_f3.value())
   380                         Sends a command in position mode   385                 self.desired_ref.velocity = [0.1, 0.1, 0.1, 0.1]
   386                 self.desired_ref.effort = [0.0, 0.0, 0.0, 0.0]
   392                         Handler call when clicking checkbox to control all fingers   406                 self._subscriber.unregister()
   409                 except ValueError, e:
   410                         rospy.logerr(
'BHandGUI: Error connecting topic (%s)'%e)
   418                         rospy.loginfo(
'BHandGUI: connection stablished with %s'%self.
_topic)
   424                         Handler for Joint States   430                 for i 
in range(len(msg.name)):
   459                         rospy.loginfo(
'BHandGUI: connection stablished with %s'%self._topic_dspic)
   466                 ret = QMessageBox.question(self.
_widget, 
"Dspic Reset Odometry", 
'Are you sure of resetting the odometry?', QMessageBox.Ok, QMessageBox.Cancel)
   468                 if ret == QMessageBox.Ok:
   472                                 ret = self._service_dspic_reset_odom(0.0, 0.0, 0.0, 0.0)                                
   473                         except ValueError, e:
   474                                 rospy.logerr(
'BHandGUI::press_reset_dspic_odom: (%s)'%e)
   475                         except rospy.ServiceException, e:
   476                                 rospy.logerr(
'BHandGUI::press_reset_dspic_odom: (%s)'%e)
   477                                 QMessageBox.warning(self.
_widget, 
"Warning", 
"Servicio no disponible")
   482                         Handles command enabled event from checkbox   486                         self._widget.checkBox_enable_control_pos.setChecked(
True)
   493                         self._widget.checkBox_enable_control_pos.setChecked(
False)
   502                         Handles command enabled event from checkbox   506                         self._widget.checkBox_enable_control_vel.setChecked(
True)
   509                         self._widget.checkBox_enable_control_vel.setChecked(
False)
   515                         Handles the click of this radio button   518                 self._timer_commands.stop()
   524                         Handles the click of this radio button   527                 self._timer_commands.start(BHAND_VELOCITY_COMMANDS_FREQ)
   532                         Calls the service to set the control mode of the hand   533                         @param mode: Desired Bhand mode of operation ('PID', 'VELOCITY')   538                 except ValueError, e:
   539                         rospy.logerr(
'BHandGUI::set_control_mode: (%s)'%e)
   540                 except rospy.ServiceException, e:
   541                         rospy.logerr(
'BHandGUI::set_control_mode: (%s)'%e)
   542                         QMessageBox.warning(self.
_widget, 
"Warning", 
"Servicio no disponible")
   547                         Calls the service to set the control mode of the hand   548                         @param action: Action number (defined in msgs/Service.msg)   553                 except ValueError, e:
   554                         rospy.logerr(
'BHandGUI::send_bhand_action: (%s)'%e)
   555                 except rospy.ServiceException, e:
   556                         rospy.logerr(
'BHandGUI::send_bhand_action: (%s)'%e)
   557                         QMessageBox.warning(self.
_widget, 
"Warning", 
"Servicio no disponible")
   562                         Sends a command to the bhand   565                 self.desired_ref.position = [0, 0, 0, 0]
   567                 self.desired_ref.effort = [0.0, 0.0, 0.0, 0.0]
   573                         Handles every timeout triggered by the Qtimer for sending commands         575                 if self.
enable_commands and self._bhand_data.control_mode == 
'VELOCITY':
   581                         Stops the movement of the joints   582                         It sets the velocity to 0   584                 self._widget.horizontalSlider_v_spread.setValue(0)
   585                 self._widget.horizontalSlider_v_f1.setValue(0)
   586                 self._widget.horizontalSlider_v_f2.setValue(0)
   587                 self._widget.horizontalSlider_v_f3.setValue(0)
   592                         Shutdowns connections   594                 self._timer_commands.stop()
   596                 self._subscriber.unregister()
   597                 self._joint_subscriber.unregister()
   598                 self._tact_subscriber.unregister()
   599                 self._publisher_command.unregister()
   600                 self._service_bhand_actions.close()
   601                 self._service_set_mode.close()
   611                 if self._bhand_data.hand_initialized:
   612                         self._widget.checkBox_hand_initialized.setChecked(1)
   614                         self._widget.checkBox_hand_initialized.setChecked(0)
   617                 if self._bhand_data.state == 100:
   619                 elif self._bhand_data.state == 200:
   621                 elif self._bhand_data.state == 300:
   623                 elif self._bhand_data.state == 400:
   625                 elif self._bhand_data.state == 500:
   627                 elif self._bhand_data.state == 600:
   633                 self._widget.lineEdit_mode.setText(self._bhand_data.control_mode)
   636                 self._widget.lineEdit_motor_pos_hz.setText(str(self._bhand_data.desired_freq))
   637                 self._widget.lineEdit_motor_pos_hz_2.setText(str(round(self._bhand_data.real_freq,1)))
   640                 self._widget.lineEdit.setText(str(self._bhand_data.temp_spread[0]))
   641                 self._widget.lineEdit_3.setText(str(self._bhand_data.temp_spread[1]))
   642                 self._widget.lineEdit_2.setText(str(self._bhand_data.temp_f1[0]))
   643                 self._widget.lineEdit_4.setText(str(self._bhand_data.temp_f1[1]))
   644                 self._widget.lineEdit_5.setText(str(self._bhand_data.temp_f2[0]))
   645                 self._widget.lineEdit_6.setText(str(self._bhand_data.temp_f2[1]))
   646                 self._widget.lineEdit_7.setText(str(self._bhand_data.temp_f3[0]))
   647                 self._widget.lineEdit_8.setText(str(self._bhand_data.temp_f3[1]))
   650                 self._widget.lineEdit_spread_des_pos.setText(str(round(self.
base_spread,3)))
   651                 self._widget.lineEdit_f1_des_pos.setText(str(round(self.
finger1_spread,3)))
   652                 self._widget.lineEdit_f2_des_pos.setText(str(round(self.
finger2_spread,3)))
   653                 self._widget.lineEdit_f3_des_pos.setText(str(round(self.
finger3_spread,3)))
   655                 self._widget.lineEdit_spread_read_pos.setText(str(round(self.
joint_state_pointer[
'SPREAD_1'][
'values'][0],3)))
   656                 self._widget.lineEdit_f1_read_pos.setText(str(round(self.
joint_state_pointer[
'F1'][
'values'][0],3)))
   657                 self._widget.lineEdit_f2_read_pos.setText(str(round(self.
joint_state_pointer[
'F2'][
'values'][0],3)))
   658                 self._widget.lineEdit_f3_read_pos.setText(str(round(self.
joint_state_pointer[
'F3'][
'values'][0],3)))
   659                 self._widget.lineEdit_spread_read_pos_2.setText(str(round(self.
joint_state_pointer[
'SPREAD_1'][
'values'][0],3)))
   660                 self._widget.lineEdit_f1_read_pos_2.setText(str(round(self.
joint_state_pointer[
'F1'][
'values'][0],3)))
   661                 self._widget.lineEdit_f2_read_pos_2.setText(str(round(self.
joint_state_pointer[
'F2'][
'values'][0],3)))
   662                 self._widget.lineEdit_f3_read_pos_2.setText(str(round(self.
joint_state_pointer[
'F3'][
'values'][0],3)))
   664                 self._widget.lineEdit_spread_des_vel.setText(str(round(self.
base_spread_vel,3)))
   670                 if self._bhand_data.state == 300:
   671                         self._widget.lineEdit_fingertip1.setText(str(round(self.
joint_state_pointer[
'F1_TIP'][
'values'][2],4)))
   672                         self._widget.lineEdit_fingertip2.setText(str(round(self.
joint_state_pointer[
'F2_TIP'][
'values'][2],4)))
   673                         self._widget.lineEdit_fingertip3.setText(str(round(self.
joint_state_pointer[
'F3_TIP'][
'values'][2],4)))
   682                 if self.
_tact_data is not None and self._bhand_data.state == 300:
   687                                         lcd_string = 
"lcdNumber" + str(i*3 + j)
   688                                         value = round(self._tact_data.finger1[(7-i)*3 + j ], 1)
   689                                         getattr(self.
_widget,lcd_string).display(value)
   690                                         if 0.0 <= value 
and value < 4.0:
   692                                         elif 4.0 <= value 
and value < 8.0:
   694                                         elif 8.0 <= value 
and value < 12.0:
   696                                         elif 12.0 <= value 
and value <= 16.0:
   700                                         getattr(self.
_widget,lcd_string).setStyleSheet(color_string)
   705                                         lcd_string = 
"lcdNumber" + str(i*3 + j) + 
"_3"   706                                         value = round(self._tact_data.finger2[(7-i)*3 + j ], 1)
   707                                         getattr(self.
_widget,lcd_string).display(value)
   708                                         if 0.0 <= value 
and value < 4.0:
   710                                         elif 4.0 <= value 
and value < 8.0:
   712                                         elif 8.0 <= value 
and value < 12.0:
   714                                         elif 12.0 <= value 
and value <= 16.0:
   718                                         getattr(self.
_widget,lcd_string).setStyleSheet(color_string)
   723                                         lcd_string = 
"lcdNumber" + str(i*3 + j) + 
"_4"   724                                         value = round(self._tact_data.finger3[(7-i)*3 + j], 1)
   725                                         getattr(self.
_widget,lcd_string).display(value)
   726                                         if 0.0 <= value 
and value < 4.0:
   728                                         elif 4.0 <= value 
and value < 8.0:
   730                                         elif 8.0 <= value 
and value < 12.0:
   732                                         elif 12.0 <= value 
and value <= 16.0:
   736                                         getattr(self.
_widget,lcd_string).setStyleSheet(color_string)
   739                         for i 
in range(0,24):
   740                                 lcd_string = 
"lcdNumber" + str(i) + 
"_6"   741                                 value = round(self._tact_data.palm[i], 1)
   742                                 getattr(self.
_widget,lcd_string).display(value)
   743                                 if 0.0 <= value 
and value < 2.5:
   745                                 elif 2.5 <= value 
and value < 5.0:
   747                                 elif 5.0 <= value 
and value < 7.5:
   749                                 elif 7.5 <= value 
and value <= 16.0:
   753                                 getattr(self.
_widget,lcd_string).setStyleSheet(color_string)
   760                         rospy.logerr(
'BHandGUI: error in communication with %s'%self.
_topic)
   761                         self._widget.qlabel_state_connection.setPixmap(self.
_pixmap_red)
   766                         self._widget.qlabel_jointstate_connection.setPixmap(self.
_pixmap_red)
   769                         self._widget.qlabel_state_connection.setPixmap(self.
_pixmap_green)
   772                         self._widget.qlabel_jointstate_connection.setPixmap(self.
_pixmap_green)
 
def shutdown_plugin(self)
 
def timeout_command_timer(self)
 
def _on_topic_changed(self)
 
def press_reset_dspic_odom(self)
 
def radio_button_velocity_clicked(self, value)
 
def open_button_pressed(self)
 
def _receive_dspic_data(self, msg)
 
def _receive_joints_data(self, msg)
 
_topic_timeout_connection
 
def enable_command_vel_changed(self, value)
 
def slider_4_changed(self)
 
def slider_3_changed(self)
 
def mode1_button_pressed(self)
 
def radio_button_position_clicked(self, value)
 
def read_ros_params(self)
 
def slider_v_f3_changed(self)
 
def send_bhand_action(self, action)
 
_topic_joint_states_timer
 
def slider_v_f1_changed(self)
 
def slider_1_changed(self)
 
def slider_v_spread_changed(self)
 
def _receive_state_data(self, msg)
 
def fingers_check_box_pressed(self, state)
 
_topic_joint_states_connected
 
def send_position_command(self)
 
def send_velocity_command(self)
 
def __init__(self, context)
 
def set_control_mode(self, mode)
 
def slider_2_changed(self)
 
def enable_command_pos_changed(self, value)
 
def start_button_pressed(self)
 
def _receive_tact_data(self, msg)
 
def mode2_button_pressed(self)
 
def slider_v_f2_changed(self)
 
def close_button_pressed(self)