rqt_bhand.py
Go to the documentation of this file.
1 # Copyright (c) 2014, Robotnik Automation
2 # All rights reserved.
3 #
4 # Redistribution and use in source and binary forms, with or without
5 # modification, are permitted provided that the following conditions
6 # are met:
7 #
8 # * Redistributions of source code must retain the above copyright
9 # notice, this list of conditions and the following disclaimer.
10 # * Redistributions in binary form must reproduce the above
11 # copyright notice, this list of conditions and the following
12 # disclaimer in the documentation and/or other materials provided
13 # with the distribution.
14 # * Neither the name of the TU Darmstadt nor the names of its
15 # contributors may be used to endorse or promote products derived
16 # from this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
21 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
22 # COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
23 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
27 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
28 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 # POSSIBILITY OF SUCH DAMAGE.
30 
31 from __future__ import division
32 import os
33 import rospkg
34 import threading
35 
36 import rospy
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
41 from rqt_gui_py.plugin import Plugin
42 
43 import time
44 import math
45 
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
50 
51 #angles
52 max_base_spread = 3.14
53 max_finger_spread = 2.44
54 
55 MAX_VELOCITY = 0.1 # rad/s
56 BHAND_VELOCITY_COMMANDS_FREQ = 50 # Frequency of vel publications in ms
57 
59 
60  def __init__(self, context):
61  super(BHandGUI, self).__init__(context)
62  self.setObjectName('BHandGUI')
63 
64  self.read_ros_params()
65  self._publisher = None
66 
67  self._widget = QWidget()
68 
69  # variable to store the sensor data when receives it
70  self._bhand_data = State()
71  self._joint_data = JointState()
72  self._tact_data = None
73 
74  rp = rospkg.RosPack()
75 
76  # Flag to enable sending commands
77  self.enable_commands = False
78 
79 
80  #Variable inits
81  # DESIRED POSITION
82  self.base_spread = 0.0
83  self.finger1_spread = 0.0
84  self.finger2_spread = 0.0
85  self.finger3_spread = 0.0
86  # DESIRED VELOCITY
87  self.base_spread_vel = 0.0
88  self.finger1_spread_vel = 0.0
89  self.finger2_spread_vel = 0.0
90  self.finger3_spread_vel = 0.0
91  self.max_vel = MAX_VELOCITY
92  self.vel_factor = self.max_vel/100.0 # For the slider
93 
94  self.red_string = "background-color: rgb(255,0,0)"
95  self.orange_string = "background-color: rgb(255,128,0)"
96  self.yellow_string = "background-color: rgb(255,255,0)"
97  self.green_string = "background-color: rgb(128,255,0)"
98  self.black_string = "background-color: rgb(0,0,0)"
99 
100  self.palm_factor = max_base_spread/99
101  self.finger_factor = max_finger_spread/99
102 
103  self.state_string = " "
104 
105 
106  # UI
107  ui_file = os.path.join(rp.get_path('rqt_bhand'), 'resource', 'BHandGUI.ui')
108  loadUi(ui_file, self._widget)
109  self._widget.setObjectName('BHandGUI')
110 
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')
113  self._pixmap_red = QPixmap(pixmap_red_file)
114  self._pixmap_green = QPixmap(pixmap_green_file)
115  self._widget.qlabel_state_connection.setPixmap(self._pixmap_red) # Shows agvs_controller comm state
116  self._widget.qlabel_jointstate_connection.setPixmap(self._pixmap_red) # Shows agvs_controller comm state
117 
118 
119  if context.serial_number() > 1:
120  self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
121 
122  # Adds this widget to the context
123  context.add_widget(self._widget)
124 
125  # Try to connect to the topic
126  self._topic = '/%s/state'%self.bhand_node_name
127  self._joint_states_topic = '/joint_states'
128  self._tact_topic = '/%s/tact_array'%self.bhand_node_name
129  self._command_topic = '/%s/command'%self.bhand_node_name
130  self._set_mode_service_name = '/%s/set_control_mode'%self.bhand_node_name
131  self._actions_service_name = '/%s/actions'%self.bhand_node_name
132 
133  # Saves the desired value
134  self.desired_ref = JointState()
135 
136  #self.joint_names = ['j11_joint', 'j32_joint', 'j12_joint', 'j22_joint', 'j23_joint', 'j13_joint', 'j33_joint']
137  #self.joint_names = ['bh_j12_joint', 'bh_j13_joint', 'bh_j22_joint', 'bh_j23_joint', 'bh_j32_joint', 'bh_j31_joint', 'bh_j11_joint', 'bh_j21_joint']
138 
139  #self.joint_ids = ['F1', 'F1_TIP', 'F2', 'F2_TIP', 'F3', 'F3_TIP', 'SPREAD_1', 'SPREAD_2']
140  # Intermediate structure to save the read positions, vels and efforts
141  # Ej.: {'j1': [ 0, 0, 0 ]}
143  for i in range(len(self.joint_ids)):
144  self.joint_state_pointer[self.joint_ids[i]] = {'joint': self.joint_names[i], 'values': [0, 0, 0]}
145  # Initializes joints data for receiving the read values
146  self._joint_data.name.append(self.joint_names[i])
147  self._joint_data.position.append(0.0)
148  self._joint_data.velocity.append(0.0)
149  self._joint_data.effort.append(0.0)
150 
151  # SUBSCRIPTIONS
152  try:
153  self._subscriber = rospy.Subscriber(self._topic, State, self._receive_state_data)
154  except ValueError, e:
155  rospy.logerr('BHandGUI: Error connecting topic (%s)'%e)
156 
157  try:
158  self._joint_subscriber = rospy.Subscriber(self._joint_states_topic, JointState, self._receive_joints_data)
159  except ValueError, e:
160  rospy.logerr('BHandGUI: Error connecting topic (%s)'%e)
161 
162  try:
163  self._tact_subscriber = rospy.Subscriber(self._tact_topic, TactileArray, self._receive_tact_data)
164  except ValueError, e:
165  rospy.logerr('BHandGUI: Error connecting topic (%s)'%e)
166 
167  # PUBLICATIONS
168  try:
169  self._publisher_command = rospy.Publisher(self._command_topic, JointState, queue_size=10)
170  except ROSException, e:
171  rospy.logerr('BHandGUI: Error creating publisher for topic %s (%s)'%(self._command_topic, e))
172 
173  # SERVICES
174  try:
175  self._service_bhand_actions = rospy.ServiceProxy(self._actions_service_name, Actions)
176  except ValueError, e:
177  rospy.logerr('BHandGUI: Error connecting service (%s)'%e)
178 
179  try:
180  self._service_set_mode = rospy.ServiceProxy(self._set_mode_service_name, SetControlMode)
181  except ValueError, e:
182  rospy.logerr('BHandGUI: Error connecting service (%s)'%e)
183 
184 
185 
186  self.fixed_fingers = 0
187 
188  # HANDLERS
189  # Adds handlers to 'press button' event
190  self._widget.pushButtonStart.clicked.connect(self.start_button_pressed)
191  self._widget.pushButton_stop.clicked.connect(self.stop)
192  self._widget.pushButton_close.clicked.connect(self.close_button_pressed)
193  self._widget.pushButton_open.clicked.connect(self.open_button_pressed)
194  self._widget.pushButton_mode1.clicked.connect(self.mode1_button_pressed)
195  self._widget.pushButton_mode2.clicked.connect(self.mode2_button_pressed)
196  self._widget.horizontalSlider.valueChanged.connect(self.slider_1_changed)
197  self._widget.horizontalSlider_2.valueChanged.connect(self.slider_2_changed)
198  self._widget.horizontalSlider_3.valueChanged.connect(self.slider_3_changed)
199  self._widget.horizontalSlider_4.valueChanged.connect(self.slider_4_changed)
200  self._widget.horizontalSlider_v_spread.valueChanged.connect(self.slider_v_spread_changed)
201  self._widget.horizontalSlider_v_f1.valueChanged.connect(self.slider_v_f1_changed)
202  self._widget.horizontalSlider_v_f2.valueChanged.connect(self.slider_v_f2_changed)
203  self._widget.horizontalSlider_v_f3.valueChanged.connect(self.slider_v_f3_changed)
204 
205  #self.connect(self._widget.checkBox_enable_control_vel, Signal("stateChanged(int)"), self.enable_command_vel_changed)
206  self._widget.checkBox_enable_control_vel.stateChanged.connect(self.enable_command_vel_changed)
207  #self.connect(self._widget.checkBox_enable_control_pos, Signal("stateChanged(int)"), self.enable_command_pos_changed)
208  self._widget.checkBox_enable_control_pos.stateChanged.connect(self.enable_command_pos_changed)
209  self._widget.checkBox_enable_control_vel.setChecked(False)
210 
211  self._widget.radioButtonPosition.clicked.connect(self.radio_button_position_clicked)
212  self._widget.radioButtonVelocity.clicked.connect(self.radio_button_velocity_clicked)
213  #self.connect(self._widget.radioButtonPosition, Signal("clicked(bool)"), self.radio_button_position_clicked)
214  #self.connect(self._widget.radioButtonVelocity, Signal("clicked(bool)"), self.radio_button_velocity_clicked)
215 
216 
217  self._widget.checkBox.stateChanged.connect(self.fingers_check_box_pressed)
218 
219 
220  self._init_timers()
221 
222 
223  def read_ros_params(self):
224  '''
225  Read ROS params from server
226  '''
227  _name = rospy.get_name()
228 
229  self.bhand_node_name = rospy.get_param('%s/bhand_node_name'%_name, 'bhand_node')
230  # Reads the configuration of the joints ids
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'])
233 
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))
237 
238 
239 
240  # inits the timers used to control the connection, ...
241  def _init_timers(self):
242  self._topic_connected = False
244 
245  self._topic_timer = time.time()
246  self._topic_joint_states_timer = time.time()
247 
248 
249 
250 
251  self._topic_timeout_connection = 5 # seconds
252  # Creates a basic timer and starts it
253  self._timer = QBasicTimer()
254  self._timer.start(1, self)
255  # Creates a timer to send command refs periodically
256  self._timer_commands = QTimer()
257  #self.connect(self._timer_commands, Signal("timeout()"), self.timeout_command_timer)
258  self._timer_commands.timeout.connect(self.timeout_command_timer)
259 
261  '''
262  Handles the press button event to call initialization service
263  '''
264  self.send_bhand_action(Service.INIT_HAND)
265  '''
266  rospy.wait_for_service(self._actions_service_name)
267  try:
268  action = rospy.ServiceProxy(self._actions_service_name, Actions)
269  resp1 = action(Service.INIT_HAND)
270  return resp1
271  except rospy.ServiceException, e:
272  rospy.logerr("Service call failed: %s"%e)
273  '''
274 
276  '''
277  Handles the press button event to call close hand service
278  '''
279  #self._widget.checkBox_enable_control_pos.setChecked(False)
280  self._widget.radioButtonPosition.setChecked(True)
281  self.send_bhand_action(Service.CLOSE_GRASP)
282 
283 
285  '''
286  Handles the press button event to call open hand service
287  '''
288  self.send_bhand_action(Service.OPEN_GRASP)
289 
290 
292  '''
293  Handles the press button event to call set mode 1 service
294  '''
295  self.send_bhand_action(Service.SET_GRASP_1)
296 
297 
299  '''
300  Handles the press button event to call set mode 2 service
301  '''
302  self.send_bhand_action(Service.SET_GRASP_2)
303 
304 
305 
306  def slider_1_changed(self):
307  self.base_spread = self._widget.horizontalSlider.value() * self.palm_factor
308  if self.enable_commands and self._bhand_data.control_mode == 'PID':
309  self.send_position_command()
310 
311 
312 
313  def slider_2_changed(self):
314  self.finger3_spread = self._widget.horizontalSlider_2.value() * self.finger_factor
315  if self.fixed_fingers == 1:
316  self.finger1_spread = self.finger2_spread = self.finger3_spread
317  self._widget.horizontalSlider_3.setSliderPosition(self._widget.horizontalSlider_2.value())
318  self._widget.horizontalSlider_4.setSliderPosition(self._widget.horizontalSlider_2.value())
319  if self.enable_commands and self._bhand_data.control_mode == 'PID':
320  self.send_position_command()
321 
322  def slider_3_changed(self):
323  self.finger1_spread = self._widget.horizontalSlider_3.value() * self.finger_factor
324  if self.fixed_fingers == 1:
325  self.finger3_spread = self.finger2_spread = self.finger1_spread
326  self._widget.horizontalSlider_2.setSliderPosition(self._widget.horizontalSlider_3.value())
327  self._widget.horizontalSlider_4.setSliderPosition(self._widget.horizontalSlider_3.value())
328  if self.enable_commands and self._bhand_data.control_mode == 'PID':
329  self.send_position_command()
330 
331  def slider_4_changed(self):
332  self.finger2_spread = self._widget.horizontalSlider_4.value() * self.finger_factor
333  if self.fixed_fingers == 1:
334  self.finger1_spread = self.finger2_spread = self.finger2_spread
335  self._widget.horizontalSlider_2.setSliderPosition(self._widget.horizontalSlider_4.value())
336  self._widget.horizontalSlider_3.setSliderPosition(self._widget.horizontalSlider_4.value())
337  if self.enable_commands and self._bhand_data.control_mode == 'PID':
338  self.send_position_command()
339 
341  '''
342  Handler for slider v_spread
343  '''
344  self.base_spread_vel = self._widget.horizontalSlider_v_spread.value() * self.vel_factor
345 
346 
348  '''
349  Handler for slider v_f1
350  '''
351  self.finger1_spread_vel = self._widget.horizontalSlider_v_f1.value() * self.vel_factor
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())
355 
356 
358  '''
359  Handler for slider v_f2
360  '''
361  self.finger2_spread_vel = self._widget.horizontalSlider_v_f2.value() * self.vel_factor
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())
365 
366 
368  '''
369  Handler for slider v_f3
370  '''
371  self.finger3_spread_vel = self._widget.horizontalSlider_v_f3.value() * self.vel_factor
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())
375 
376 
377 
379  '''
380  Sends a command in position mode
381  '''
382 
383  self.desired_ref.name = [self.joint_state_pointer['SPREAD_1']['joint'], self.joint_state_pointer['F3']['joint'], self.joint_state_pointer['F1']['joint'], self.joint_state_pointer['F2']['joint']]
384  self.desired_ref.position = [self.base_spread, self.finger3_spread, self.finger1_spread, self.finger2_spread]
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]
387  self._publisher_command.publish(self.desired_ref)
388 
389 
390  def fingers_check_box_pressed(self, state):
391  '''
392  Handler call when clicking checkbox to control all fingers
393  '''
394  if state == 0:
395  self.fixed_fingers = 0
396  elif state == 2:
397  self.fixed_fingers = 1
398 
399 
400 
401  @Slot(str)
402  # Handles the change of topic's name
403  def _on_topic_changed(self):
404  # reads the topic's name from the 'QLineEdit' 'topic_line_edit' (in the .ui file)
405  #self._topic = self._widget.topic_line_edit.text()
406  self._subscriber.unregister()
407  try:
408  self._subscriber = rospy.Subscriber(self._topic, State, self._receive_state_data)
409  except ValueError, e:
410  rospy.logerr('BHandGUI: Error connecting topic (%s)'%e)
411 
412  # Handles the messages from the agvs controller
413  def _receive_state_data(self, msg):
414  self._bhand_data = msg
415  self._topic_timer = time.time()
416 
417  if not self._topic_connected:
418  rospy.loginfo('BHandGUI: connection stablished with %s'%self._topic)
419  self._topic_connected = True
420 
421 
422  def _receive_joints_data(self, msg):
423  '''
424  Handler for Joint States
425  '''
426  self._joints_data = msg
427 
428  self._topic_joint_states_timer = time.time()
429 
430  for i in range(len(msg.name)):
431  for j in self.joint_state_pointer:
432  if self.joint_state_pointer[j]['joint'] == msg.name[i]:
433  self.joint_state_pointer[j]['values'] = [msg.position[i], msg.velocity[i], msg.effort[i]]
434 
435 
436  if not self._topic_joint_states_connected:
437  rospy.loginfo('Bhand: connection stablished with %s'%self._joint_states_topic)
439 
440 
441 
442 
443  def _receive_tact_data(self, msg):
444 
445  if self._tact_data is None:
446  self._tact_data = TactileArray()
447 
448  self._tact_data = msg
449 
450 
451 
452 
453  # Handles the messages from the dspic controller
454  def _receive_dspic_data(self, msg):
455  self._dspic_data = msg
456  self._topic_dspic_timer = time.time()
457 
458  if not self._topic_dspic_connected:
459  rospy.loginfo('BHandGUI: connection stablished with %s'%self._topic_dspic)
461 
462 
463  # Handles the press event of the button dspic reset odom
465 
466  ret = QMessageBox.question(self._widget, "Dspic Reset Odometry", 'Are you sure of resetting the odometry?', QMessageBox.Ok, QMessageBox.Cancel)
467 
468  if ret == QMessageBox.Ok:
469 
470  # Call the service recalibrate dspic
471  try:
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")
478 
479 
480  def enable_command_vel_changed(self, value):
481  '''
482  Handles command enabled event from checkbox
483  '''
484 
485  if value != 0:
486  self._widget.checkBox_enable_control_pos.setChecked(True)
487  self.enable_commands = True
488  #if self._bhand_data.control_mode == 'VELOCITY':
489  # self._timer_commands.start(BHAND_VELOCITY_COMMANDS_FREQ)
490 
491 
492  else:
493  self._widget.checkBox_enable_control_pos.setChecked(False)
494  self.enable_commands = False
495  #if self._bhand_data.control_mode == 'VELOCITY':
496  # self._timer_commands.stop()
497 
498 
499 
500  def enable_command_pos_changed(self, value):
501  '''
502  Handles command enabled event from checkbox
503  '''
504 
505  if value != 0:
506  self._widget.checkBox_enable_control_vel.setChecked(True)
507  self.enable_commands = True
508  else:
509  self._widget.checkBox_enable_control_vel.setChecked(False)
510  self.enable_commands = False
511 
512 
514  '''
515  Handles the click of this radio button
516  '''
517  self.set_control_mode('PID')
518  self._timer_commands.stop()
519  self.stop()
520 
521 
523  '''
524  Handles the click of this radio button
525  '''
526  self.set_control_mode('VELOCITY')
527  self._timer_commands.start(BHAND_VELOCITY_COMMANDS_FREQ)
528 
529 
530  def set_control_mode(self, mode):
531  '''
532  Calls the service to set the control mode of the hand
533  @param mode: Desired Bhand mode of operation ('PID', 'VELOCITY')
534  @type mode: string
535  '''
536  try:
537  ret = self._service_set_mode(mode)
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")
543 
544 
545  def send_bhand_action(self, action):
546  '''
547  Calls the service to set the control mode of the hand
548  @param action: Action number (defined in msgs/Service.msg)
549  @type action: int
550  '''
551  try:
552  ret = self._service_bhand_actions(action)
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")
558 
559 
561  '''
562  Sends a command to the bhand
563  '''
564  self.desired_ref.name = [self.joint_state_pointer['SPREAD_1']['joint'], self.joint_state_pointer['F3']['joint'], self.joint_state_pointer['F1']['joint'], self.joint_state_pointer['F2']['joint']]
565  self.desired_ref.position = [0, 0, 0, 0]
566  self.desired_ref.velocity = [self.base_spread_vel, self.finger3_spread_vel, self.finger1_spread_vel, self.finger2_spread_vel]
567  self.desired_ref.effort = [0.0, 0.0, 0.0, 0.0]
568  self._publisher_command.publish(self.desired_ref)
569 
570 
572  '''
573  Handles every timeout triggered by the Qtimer for sending commands
574  '''
575  if self.enable_commands and self._bhand_data.control_mode == 'VELOCITY':
576  self.send_velocity_command()
577 
578 
579  def stop(self):
580  '''
581  Stops the movement of the joints
582  It sets the velocity to 0
583  '''
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)
588 
589 
590  def shutdown_plugin(self):
591  '''
592  Shutdowns connections
593  '''
594  self._timer_commands.stop()
595  self._timer.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()
602 
603 
604  # Method executed periodically
605  # Updates the graphical qt components
606  def timerEvent(self, e):
607 
608  #state = self._bhand_data.state
609 
610  #Initialized?
611  if self._bhand_data.hand_initialized:
612  self._widget.checkBox_hand_initialized.setChecked(1)
613  else:
614  self._widget.checkBox_hand_initialized.setChecked(0)
615 
616  #State
617  if self._bhand_data.state == 100:
618  self.state_string = "INIT_STATE"
619  elif self._bhand_data.state == 200:
620  self.state_string = "STANDBY_STATE"
621  elif self._bhand_data.state == 300:
622  self.state_string = "READY_STATE"
623  elif self._bhand_data.state == 400:
624  self.state_string = "EMERGENCY_STATE"
625  elif self._bhand_data.state == 500:
626  self.state_string = "FAILURE_STATE"
627  elif self._bhand_data.state == 600:
628  self.state_string = "SHUTDOWN_STATE"
629 
630  if self.state_string != " ":
631  self._widget.lineEdit_state.setText(self.state_string)
632 
633  self._widget.lineEdit_mode.setText(self._bhand_data.control_mode)
634 
635  #Frequencies
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)))
638 
639  #Temperatures
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]))
648 
649  # Desired Control Positions
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)))
654  # Read Control Positions
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)))
663  # Desired velocities
664  self._widget.lineEdit_spread_des_vel.setText(str(round(self.base_spread_vel,3)))
665  self._widget.lineEdit_f1_des_vel.setText(str(round(self.finger1_spread_vel,3)))
666  self._widget.lineEdit_f2_des_vel.setText(str(round(self.finger2_spread_vel,3)))
667  self._widget.lineEdit_f3_des_vel.setText(str(round(self.finger3_spread_vel,3)))
668 
669  #Effort
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)))
674 
675  #Tactile sensors
676 
677  #self.red = 255
678  #self.green = 255
679  #self.blue = 0
680  #color_string = "background-color: rgb(" + str(self.red) + "," + str(self.green) + "," + str(self.blue) + ")"
681 
682  if self._tact_data is not None and self._bhand_data.state == 300:
683 
684  #Finger 1
685  for i in range(0,8):
686  for j in range(0,3):
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:
691  color_string = self.green_string
692  elif 4.0 <= value and value < 8.0:
693  color_string = self.yellow_string
694  elif 8.0 <= value and value < 12.0:
695  color_string = self.orange_string
696  elif 12.0 <= value and value <= 16.0:
697  color_string = self.red_string
698  else:
699  color_string = self.black_string
700  getattr(self._widget,lcd_string).setStyleSheet(color_string)
701 
702  #Finger 2
703  for i in range(0,8):
704  for j in range(0,3):
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:
709  color_string = self.green_string
710  elif 4.0 <= value and value < 8.0:
711  color_string = self.yellow_string
712  elif 8.0 <= value and value < 12.0:
713  color_string = self.orange_string
714  elif 12.0 <= value and value <= 16.0:
715  color_string = self.red_string
716  else:
717  color_string = self.black_string
718  getattr(self._widget,lcd_string).setStyleSheet(color_string)
719 
720  #Finger 3
721  for i in range(0,8):
722  for j in range(0,3):
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:
727  color_string = self.green_string
728  elif 4.0 <= value and value < 8.0:
729  color_string = self.yellow_string
730  elif 8.0 <= value and value < 12.0:
731  color_string = self.orange_string
732  elif 12.0 <= value and value <= 16.0:
733  color_string = self.red_string
734  else:
735  color_string = self.black_string
736  getattr(self._widget,lcd_string).setStyleSheet(color_string)
737 
738  #Palm
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:
744  color_string = self.green_string
745  elif 2.5 <= value and value < 5.0:
746  color_string = self.yellow_string
747  elif 5.0 <= value and value < 7.5:
748  color_string = self.orange_string
749  elif 7.5 <= value and value <= 16.0:
750  color_string = self.red_string
751  else:
752  color_string = self.black_string
753  getattr(self._widget,lcd_string).setStyleSheet(color_string)
754 
755 
756  # Checks the ROS connection
757  t = time.time()
758  if self._topic_connected and (t - self._topic_timer >= self._topic_timeout_connection):
759  self._topic_connected = False
760  rospy.logerr('BHandGUI: error in communication with %s'%self._topic)
761  self._widget.qlabel_state_connection.setPixmap(self._pixmap_red)
762 
764  self._topic_joint_states_connected = False
765  rospy.logerr('BHandGUI: error in communication with %s'%self._joint_states_topic)
766  self._widget.qlabel_jointstate_connection.setPixmap(self._pixmap_red)
767 
768  if self._topic_connected:
769  self._widget.qlabel_state_connection.setPixmap(self._pixmap_green)
770 
772  self._widget.qlabel_jointstate_connection.setPixmap(self._pixmap_green)
def radio_button_velocity_clicked(self, value)
Definition: rqt_bhand.py:522
def _receive_dspic_data(self, msg)
Definition: rqt_bhand.py:454
def _receive_joints_data(self, msg)
Definition: rqt_bhand.py:422
def enable_command_vel_changed(self, value)
Definition: rqt_bhand.py:480
def radio_button_position_clicked(self, value)
Definition: rqt_bhand.py:513
def send_bhand_action(self, action)
Definition: rqt_bhand.py:545
def _receive_state_data(self, msg)
Definition: rqt_bhand.py:413
def fingers_check_box_pressed(self, state)
Definition: rqt_bhand.py:390
def __init__(self, context)
Definition: rqt_bhand.py:60
def set_control_mode(self, mode)
Definition: rqt_bhand.py:530
def enable_command_pos_changed(self, value)
Definition: rqt_bhand.py:500
def _receive_tact_data(self, msg)
Definition: rqt_bhand.py:443


rqt_bhand
Author(s): Román Navarro , Jorge Ariño
autogenerated on Thu Aug 1 2019 03:30:52