advanced_controls.py
Go to the documentation of this file.
1 # Copyright (c) 2011, Dirk Thomas, TU Darmstadt
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 
32 import os
33 import rospy
34 import rospkg
35 
36 from time import sleep
37 
38 from qt_gui.plugin import Plugin
39 from python_qt_binding import loadUi
40 
41 from QtWidgets import QMessageBox, QWidget
42 from QtGui import QIcon
43 from controller_manager_msgs.srv import ListControllers
44 from controller_manager_msgs.srv import SwitchController, LoadController
45 from sr_robot_msgs.srv import ChangeControlType
46 from sr_robot_msgs.msg import ControlType
47 from sr_utilities.hand_finder import HandFinder
48 
49 
51 
52  """
53  A rosgui plugin for loading the different controllers
54  """
55  ICON_DIR = os.path.join(
56  rospkg.RosPack().get_path('sr_visualization_icons'), 'icons')
57  CONTROLLER_ON_ICON = QIcon(os.path.join(ICON_DIR, 'green.png'))
58  CONTROLLER_OFF_ICON = QIcon(os.path.join(ICON_DIR, 'red.png'))
59 
61 
62  self.hand_ids = []
63  hand_joint_prefixes = []
64  # mapping is always in global ns
65  if rospy.has_param("/hand/mapping"):
66  hand_mapping = rospy.get_param("/hand/mapping")
67  for _, value in hand_mapping.items():
68  # if prefix matches the mapping, add this hand
69  # empty prefix means both hands
70  if self._prefix in value:
71  self.hand_ids.append(value)
72  else:
73  self.hand_ids.append("")
74 
75  if rospy.has_param("/hand/joint_prefix"):
76  hand_joint_prefix_mapping = rospy.get_param("/hand/joint_prefix")
77  for _, value in hand_joint_prefix_mapping.items():
78  # if prefix matches the mapping, add this hand
79  # empty prefix means both hands
80  if self._prefix in value:
81  hand_joint_prefixes.append(value)
82  if len(hand_joint_prefixes) == 0:
83  QMessageBox.warning(self._widget, "Warning",
84  "No hand found with prefix :" + self._prefix)
85  hand_joint_prefixes.append("")
86  else:
87  rospy.loginfo("no joint prefix found, not appending prefix")
88  hand_joint_prefixes.append("")
89 
90  joints = ["ffj0", "ffj3", "ffj4",
91  "mfj0", "mfj3", "mfj4",
92  "rfj0", "rfj3", "rfj4",
93  "lfj0", "lfj3", "lfj4", "lfj5",
94  "thj1", "thj2", "thj3", "thj4", "thj5",
95  "wrj1", "wrj2"]
96  self.controllers = {
97  "effort": [
98  "sh_{0}{1}_effort_controller".format(hand_joint_prefix, joint)
99  for joint in joints for hand_joint_prefix in
100  hand_joint_prefixes],
101  "position": [
102  "sh_{0}{1}_position_controller".format(hand_joint_prefix,
103  joint)
104  for joint in joints for hand_joint_prefix in
105  hand_joint_prefixes],
106  "mixed": [
107  "sh_{0}{1}_mixed_position_velocity_controller".format(
108  hand_joint_prefix, joint)
109  for joint in joints for hand_joint_prefix in
110  hand_joint_prefixes],
111  "velocity": [
112  "sh_{0}{1}_velocity_controller".format(
113  hand_joint_prefix, joint)
114  for joint in joints for hand_joint_prefix in
115  hand_joint_prefixes], "stop": []}
116 
118  cont for type_conts in self.controllers.itervalues()
119  for cont in type_conts]
120 
121  def __init__(self, context):
122  super(SrGuiAdvancedControls, self).__init__(context)
123  self.setObjectName('SrGuiAdvancedControls')
124 
125  self._publisher = None
126 
127  self._widget = QWidget()
128 
129  ui_file = os.path.join(
130  rospkg.RosPack().get_path('sr_gui_advanced_controls'), 'uis',
131  'SrAdvancedControls.ui')
132  loadUi(ui_file, self._widget)
133  self._widget.setObjectName('SrAdvancedControlsUI')
134  context.add_widget(self._widget)
135 
136  # setting the prefixes
137  self._hand_finder = HandFinder()
138  hand_parameters = self._hand_finder.get_hand_parameters()
139 
140  self._prefix = ""
141  for hand in hand_parameters.mapping:
142  self._widget.select_prefix.addItem(hand_parameters.mapping[hand])
143 
144  if not hand_parameters.mapping:
145  rospy.logerr("No hand detected")
146  QMessageBox.warning(
147  self._widget, "warning", "No hand is detected")
148  else:
149  self._widget.select_prefix.setCurrentIndex(0)
150  self._prefix = hand_parameters.mapping.values()[0]
151 
152  self._widget.select_prefix.currentIndexChanged['QString'].connect(
153  self.prefix_selected)
154 
155  self.populate_controllers()
156 
157  # Setting the initial state of the controller buttons
158  self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
159  self._widget.btn_mixed.setChecked(False)
160  self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
161  self._widget.btn_effort.setChecked(False)
162  self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
163  self._widget.btn_position.setChecked(False)
164  self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
165  self._widget.btn_velocity.setChecked(False)
166 
167  # attaching the button press event to their actions
168  self._widget.btn_stop.pressed.connect(self.on_stop_ctrl_clicked_)
169  self._widget.btn_effort.pressed.connect(self.on_effort_ctrl_clicked_)
170  self._widget.btn_position.pressed.connect(
172  self._widget.btn_mixed.pressed.connect(self.on_mixed_ctrl_clicked_)
173  self._widget.btn_velocity.pressed.connect(
175 
176  # check the correct control box, depending on PWM_CONTROL env variable
177  if os.environ.get('PWM_CONTROL') in [None, '0']:
178  self._widget.radioButtonTorque.setChecked(True)
179  self._widget.radioButtonPWM.setChecked(False)
180  else:
181  self._widget.radioButtonTorque.setChecked(False)
182  self._widget.radioButtonPWM.setChecked(True)
183 
184  self._widget.radioButtonTorque.toggled.connect(
186  self._widget.radioButtonPWM.toggled.connect(
188 
190  """
191  Switch between FORCE, PWM modes
192  We only react to the currently ON radio button event
193  """
194  if checked:
195  change_type_msg = ChangeControlType()
196  if self._widget.radioButtonTorque.isChecked():
197  change_type_msg.control_type = ControlType.FORCE
198  rospy.loginfo("Change Control mode to FORCE")
199  else:
200  change_type_msg.control_type = ControlType.PWM
201  rospy.loginfo("Change Control mode to PWM")
202  self.change_force_ctrl_type(change_type_msg)
203 
205  """
206  Stop controller
207  """
208  self._widget.btn_stop.setEnabled(False)
209  self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
210  self._widget.btn_mixed.setChecked(False)
211  self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
212  self._widget.btn_effort.setChecked(False)
213  self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
214  self._widget.btn_position.setChecked(False)
215  self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
216  self._widget.btn_velocity.setChecked(False)
217  self.change_ctrl("stop")
218  self._widget.btn_stop.setEnabled(True)
219 
221  """
222  Effort controller selected
223  """
224  self._widget.btn_effort.setEnabled(False)
225  if not self._widget.btn_effort.isChecked():
226  self._widget.btn_effort.setIcon(self.CONTROLLER_ON_ICON)
227  self._widget.btn_effort.setChecked(True)
228  self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
229  self._widget.btn_position.setChecked(False)
230  self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
231  self._widget.btn_mixed.setChecked(False)
232  self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
233  self._widget.btn_velocity.setChecked(False)
234  rospy.loginfo("Effort checked: " + str(
235  self._widget.btn_effort.isChecked()))
236  self.change_ctrl("effort")
237  else:
238  self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
239  self._widget.btn_effort.setChecked(False)
240  rospy.loginfo("Effort checked: " + str(
241  self._widget.btn_effort.isChecked()))
242  self.change_ctrl("stop")
243  self._widget.btn_effort.setEnabled(True)
244 
246  """
247  Position controller selected
248  """
249  self._widget.btn_position.setEnabled(False)
250  if not self._widget.btn_position.isChecked():
251  self._widget.btn_position.setIcon(self.CONTROLLER_ON_ICON)
252  self._widget.btn_position.setChecked(True)
253  self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
254  self._widget.btn_effort.setChecked(False)
255  self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
256  self._widget.btn_mixed.setChecked(False)
257  self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
258  self._widget.btn_velocity.setChecked(False)
259  rospy.loginfo("Position checked: " +
260  str(self._widget.btn_position.isChecked()))
261  self.change_ctrl("position")
262  else:
263  self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
264  self._widget.btn_position.setChecked(False)
265  rospy.loginfo("Position checked: " +
266  str(self._widget.btn_position.isChecked()))
267  self.change_ctrl("stop")
268  self._widget.btn_position.setEnabled(True)
269 
271  """
272  Mixed controller selected
273  """
274  self._widget.btn_mixed.setEnabled(False)
275  if not self._widget.btn_mixed.isChecked():
276  self._widget.btn_mixed.setIcon(self.CONTROLLER_ON_ICON)
277  self._widget.btn_mixed.setChecked(True)
278  self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
279  self._widget.btn_effort.setChecked(False)
280  self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
281  self._widget.btn_position.setChecked(False)
282  self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
283  self._widget.btn_velocity.setChecked(False)
284  rospy.loginfo("Mixed checked: " +
285  str(self._widget.btn_mixed.isChecked()))
286  self.change_ctrl("mixed")
287  else:
288  self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
289  self._widget.btn_mixed.setChecked(False)
290  rospy.loginfo("Mixed checked: " +
291  str(self._widget.btn_mixed.isChecked()))
292  self.change_ctrl("stop")
293  self._widget.btn_mixed.setEnabled(True)
294 
296  """
297  Velocity controller selected
298  """
299  self._widget.btn_velocity.setEnabled(False)
300  if not self._widget.btn_velocity.isChecked():
301  self._widget.btn_velocity.setIcon(self.CONTROLLER_ON_ICON)
302  self._widget.btn_velocity.setChecked(True)
303  self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
304  self._widget.btn_effort.setChecked(False)
305  self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
306  self._widget.btn_position.setChecked(False)
307  self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
308  self._widget.btn_mixed.setChecked(False)
309  rospy.loginfo("Velocity checked: " +
310  str(self._widget.btn_velocity.isChecked()))
311  self.change_ctrl("velocity")
312  else:
313  self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
314  self._widget.btn_velocity.setChecked(False)
315  rospy.loginfo("Velocity checked: " +
316  str(self._widget.btn_velocity.isChecked()))
317  self.change_ctrl("stop")
318  self._widget.btn_velocity.setEnabled(True)
319 
320  def change_ctrl(self, controller):
321  """
322  Switch the current controller
323  """
324  success = True
325  list_controllers = rospy.ServiceProxy(
326  'controller_manager/list_controllers', ListControllers)
327  try:
328  resp1 = list_controllers()
329  except rospy.ServiceException:
330  success = False
331 
332  if success:
333  controllers_to_stop = [
334  c.name for c in resp1.controller
335  if c.state == "running" and c.name in self.managed_controllers]
336  all_loaded_controllers = [c.name for c in resp1.controller]
337 
338  controllers_to_start = self.controllers[controller]
339 
340  load_controllers = None
341  for load_control in controllers_to_start:
342  if load_control not in all_loaded_controllers:
343  try:
344  load_controllers = rospy.ServiceProxy(
345  'controller_manager/load_controller',
346  LoadController)
347  resp1 = load_controllers(load_control)
348  except rospy.ServiceException:
349  success = False
350  if not resp1.ok:
351  success = False
352 
353  switch_controllers = rospy.ServiceProxy(
354  'controller_manager/switch_controller', SwitchController)
355  try:
356  resp1 = switch_controllers(
357  controllers_to_start, controllers_to_stop,
358  SwitchController._request_class.BEST_EFFORT, False, 0)
359  except rospy.ServiceException:
360  success = False
361 
362  if not resp1.ok:
363  success = False
364 
365  if not success:
366  rospy.logwarn(
367  "Failed to change some of the controllers. "
368  "This is normal if this is not a 5 finger hand.")
369 
370  def change_force_ctrl_type(self, chng_type_msg):
371  """
372  Calls the service (sr_hand_robot/change_control_type) that allows to
373  tell the driver (sr_robot_lib)
374  which type of force control has to be sent to the motor:
375  - torque demand (sr_robot_msgs::ControlType::FORCE)
376  - PWM (sr_robot_msgs::ControlType::PWM)
377  it will deactivate the Effort, Position, Mixed and Velocity buttons
378  for 3 secs to allow hardware controllers to be updated
379  """
380  success = True
381  for hand_id in self.hand_ids:
382  srv_path = 'sr_hand_robot/' + hand_id + '/change_control_type'
383  # remove double slash for empty hand_id
384  srv_path.replace("//", "/")
385  change_control_type = rospy.ServiceProxy(srv_path,
386  ChangeControlType)
387  try:
388  resp1 = change_control_type(chng_type_msg)
389  if resp1.result.control_type != chng_type_msg.control_type:
390  success = False
391  except rospy.ServiceException:
392  success = False
393 
394  # Disable buttons for 3 secs until motors change their parameters
395  self._widget.btn_effort.setEnabled(False)
396  self._widget.btn_position.setEnabled(False)
397  self._widget.btn_mixed.setEnabled(False)
398  self._widget.btn_velocity.setEnabled(False)
399  sleep(3)
400  self._widget.btn_effort.setEnabled(True)
401  self._widget.btn_position.setEnabled(True)
402  self._widget.btn_mixed.setEnabled(True)
403  self._widget.btn_velocity.setEnabled(True)
404 
405  if not success:
406  QMessageBox.warning(self._widget, "Warning",
407  "Failed to change the control type.")
408 
409  def prefix_selected(self, prefix):
410  self._prefix = prefix
411  self.populate_controllers()
412 
414  if self._publisher is not None:
415  self._publisher.unregister()
416  self._publisher = None
417 
418  def shutdown_plugin(self):
419  self._unregisterPublisher()
420 
421  def save_settings(self, global_settings, perspective_settings):
422  pass
423 
424  def restore_settings(self, global_settings, perspective_settings):
425  pass
def save_settings(self, global_settings, perspective_settings)
def restore_settings(self, global_settings, perspective_settings)


sr_gui_advanced_controls
Author(s): Ugo Cupcic
autogenerated on Wed Oct 14 2020 03:22:46