controller_tuner.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2011 Shadow Robot Company Ltd.
4 #
5 # This program is free software: you can redistribute it and/or modify it
6 # under the terms of the GNU General Public License as published by the Free
7 # Software Foundation version 2 of the License.
8 #
9 # This program is distributed in the hope that it will be useful, but WITHOUT
10 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
11 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
12 # more details.
13 #
14 # You should have received a copy of the GNU General Public License along
15 # with this program. If not, see <http://www.gnu.org/licenses/>.
16 #
17 
18 import os
19 import subprocess
20 import math
21 import time
22 import rospy
23 import rosparam
24 import rospkg
25 
26 from qt_gui.plugin import Plugin
27 from python_qt_binding import loadUi
28 
29 from QtCore import Qt, QThread
30 from QtWidgets import QMessageBox, QWidget, QTreeWidgetItem, QCheckBox,\
31  QSpinBox, QDoubleSpinBox, QFileDialog, QFrame, QPushButton, QHBoxLayout
32 from functools import partial
33 from tempfile import NamedTemporaryFile
34 
35 from sensor_msgs.msg import JointState
36 
37 from sr_gui_controller_tuner.sr_controller_tuner import SrControllerTunerApp
38 from sr_utilities.hand_finder import HandFinder
39 
40 
41 class PlotThread(QThread):
42 
43  def __init__(self, parent=None, joint_name="FFJ0", controller_type="Motor Force"):
44  QThread.__init__(self, parent)
45  self.joint_name_ = joint_name
46  self.is_joint_0_ = False
48  try:
50  "FFJ0", "MFJ0", "RFJ0", "LFJ0"].index(self.joint_name_)
51  self.is_joint_0_ = True
52  except ValueError:
53  self.is_joint_0_ = False
54 
55  self.controller_type_ = controller_type
56 
57  # prepares the title for the plot (can't contain spaces)
58  self.plot_title_ = self.joint_name_ + " " + self.controller_type_
59  self.plot_title_ = self.plot_title_.replace(" ", "_").replace("/", "_")
60 
61  # stores the subprocesses to be able to terminate them on close
62  self.subprocess_ = []
63 
64  def run(self):
65  """
66  Creates an appropriate plot according to controller type
67  Also creates a subscription if controller is of Motor Force type
68  """
69  # rxplot_str = "rxplot -b 30 -p 30 --title=" + self.plot_title_ + " "
70  rxplot_str = "rosrun rqt_plot rqt_plot "
71 
72  if self.controller_type_ == "Motor Force":
73  # the joint 0s are published on a different topic:
74  # /joint_0s/joint_states
75  if not self.is_joint_0_:
76  # subscribe to joint_states to get the index of the joint in
77  # the message
78  self.subscriber_ = rospy.Subscriber(
79  "joint_states", JointState, self.js_callback_)
80 
81  # wait until we got the joint index in the joint
82  # states message
83  while self.joint_index_in_joint_state_ is None:
84  time.sleep(0.01)
85 
86  rxplot_str += "joint_states/effort[" + str(
87  self.joint_index_in_joint_state_) + "]"
88  else:
89  rxplot_str += "joint_0s/joint_states/effort[" + str(
90  self.joint_index_in_joint_state_) + "]"
91 
92  elif self.controller_type_ == "Position":
93  rxplot_str += "sh_" + self.joint_name_.lower() + "_position_controller/state/set_point,sh_" + \
94  self.joint_name_.lower() + "_position_controller/state/process_value sh_" + \
95  self.joint_name_.lower() + "_position_controller/state/command"
96  elif self.controller_type_ == "Muscle Position":
97  rxplot_str += "sh_" + self.joint_name_.lower() + "_muscle_position_controller/state/set_point,sh_" + \
98  self.joint_name_.lower() + "_muscle_position_controller/state/process_value sh_" + \
99  self.joint_name_.lower() + "_muscle_position_controller/state/pseudo_command sh_" + \
100  self.joint_name_.lower() + "_muscle_position_controller/state/valve_muscle_0,sh_" + \
101  self.joint_name_.lower() + "_muscle_position_controller/state/valve_muscle_1"
102  elif self.controller_type_ == "Velocity":
103  rxplot_str += "sh_" + self.joint_name_.lower() + "_velocity_controller/state/set_point,sh_" + \
104  self.joint_name_.lower() + "_velocity_controller/state/process_value"
105  elif self.controller_type_ == "Mixed Position/Velocity":
106  rxplot_str += "sh_" + \
107  self.joint_name_.lower() + "_mixed_position_velocity_controller/state/set_point,sh_" + \
108  self.joint_name_.lower() + "_mixed_position_velocity_controller/state/process_value sh_" + \
109  self.joint_name_.lower() + "_mixed_position_velocity_controller/state/process_value_dot," + \
110  "sh_" + \
111  self.joint_name_.lower() + \
112  "_mixed_position_velocity_controller/state/commanded_velocity " + \
113  "sh_" + \
114  self.joint_name_.lower() + "_mixed_position_velocity_controller/state/command,sh_" + \
115  self.joint_name_.lower() + \
116  "_mixed_position_velocity_controller/state/measured_effort,sh_" + \
117  self.joint_name_.lower() + "_mixed_position_velocity_controller/state/friction_compensation"
118  elif self.controller_type_ == "Effort":
119  rxplot_str += "sh_" + self.joint_name_.lower() + "_effort_controller/state/set_point,sh_" + \
120  self.joint_name_.lower() + "_effort_controller/state/process_value"
121 
122  self.subprocess_.append(subprocess.Popen(rxplot_str.split()))
123 
124  def js_callback_(self, msg):
125  # get the joint index once, then unregister
126  self.joint_index_in_joint_state_ = msg.name.index(
127  self.joint_name_.upper())
128  self.subscriber_.unregister()
129  self.subscriber_ = None
130 
131  def __del__(self):
132  for subprocess in self.subprocess_:
133  # killing the rxplot to close the window
134  subprocess.kill()
135 
136  if self.subscriber_ is not None:
137  self.subscriber_.unregister()
138  self.subscriber_ = None
139 
140  self.wait()
141 
142 
143 class MoveThread(QThread):
144 
145  def __init__(self, parent=None, joint_name="FFJ0", controller_type="Motor Force"):
146  QThread.__init__(self, parent)
147  self.joint_name_ = joint_name
148  self.controller_type_ = controller_type
149  self.btn = parent
150  self.subprocess_ = []
151 
152  def run(self):
153  self.launch_()
154 
155  def __del__(self):
156  for subprocess in self.subprocess_:
157  subprocess.terminate()
158  self.wait()
159 
161  """
162  Create a launch file dynamically
163  """
164  # Not using automatic move for velocity and effort controllers
165  controller_name_ = ""
166  message_type = "ros"
167  if self.controller_type_ == "Position":
168  controller_name_ = "sh_" + \
169  self.joint_name_.lower() + "_position_controller"
170  if self.controller_type_ == "Muscle Position":
171  controller_name_ = "sh_" + \
172  self.joint_name_.lower() + "_muscle_position_controller"
173  elif self.controller_type_ == "Mixed Position/Velocity":
174  controller_name_ = "sh_" + \
175  self.joint_name_.lower() + \
176  "_mixed_position_velocity_controller"
177  message_type = "sr"
178 
179  min_max = self.get_min_max_()
180  namespace = rospy.get_namespace()
181 
182  string = "<launch> <node ns=\"" + namespace + \
183  "\" pkg=\"sr_movements\" name=\"sr_movements\" type=\"sr_movements\">"
184  string += "<remap from=\"~targets\" to=\"" + \
185  controller_name_ + "/command\"/>"
186  string += "<remap from=\"~inputs\" to=\"" + \
187  controller_name_ + "/state\"/>"
188  string += "<param name=\"image_path\" value=\"$(find sr_movements)/movements/test.png\"/>"
189  string += "<param name=\"min\" value=\"" + str(min_max[0]) + "\"/>"
190  string += "<param name=\"max\" value=\"" + str(min_max[1]) + "\"/>"
191  string += "<param name=\"publish_rate\" value=\"100\"/>"
192  string += "<param name=\"repetition\" value=\"1000\"/>"
193  string += "<param name=\"nb_step\" value=\"10000\"/>"
194  string += "<param name=\"msg_type\" value=\"{}\"/>".format(
195  message_type)
196  string += "</node> </launch>"
197  tmp_launch_file = NamedTemporaryFile(delete=False)
198 
199  tmp_launch_file.writelines(string)
200  tmp_launch_file.close()
201 
202  return tmp_launch_file.name
203 
204  def get_min_max_(self):
205  """
206  Retrieve joint limits in radians for joint in self.joint_name
207  """
208  # assuming 4 character joint names at the end and trimming any prefix
209  # TODO: Shouldn't this be read from the URDF ?
210  joint_name = self.joint_name_[-4:]
211  if joint_name in ["FFJ0", "MFJ0", "RFJ0", "LFJ0"]:
212  return [0.0, math.radians(180.0)]
213  elif joint_name in ["FFJ3", "MFJ3", "RFJ3", "LFJ3", "THJ1"]:
214  return [0.0, math.radians(90.0)]
215  elif joint_name in ["LFJ5"]:
216  return [0.0, math.radians(45.0)]
217  elif joint_name in ["FFJ4", "MFJ4", "RFJ4", "LFJ4"]:
218  return [math.radians(-20.0), math.radians(20.0)]
219  elif joint_name in ["THJ2"]:
220  return [math.radians(-40.0), math.radians(40.0)]
221  elif joint_name in ["THJ3"]:
222  return [math.radians(-15.0), math.radians(15.0)]
223  elif joint_name in ["THJ4"]:
224  return [math.radians(0.0), math.radians(70.0)]
225  elif joint_name in ["THJ5"]:
226  return [math.radians(-60.0), math.radians(60.0)]
227  elif joint_name in ["WRJ1"]:
228  return [math.radians(-30.0), math.radians(45.0)]
229  elif joint_name in ["WRJ2"]:
230  return [math.radians(-30.0), math.radians(10.0)]
231 
232  def launch_(self):
233  """
234  launch a dynamically created launch file
235  """
236  filename = self.create_launch_file_()
237 
238  launch_string = "roslaunch " + filename
239 
240  self.subprocess_.append(subprocess.Popen(launch_string.split()))
241 
242 
244 
245  """
246  a rosgui plugin for tuning the sr_mechanism_controllers
247  """
248 
249  def __init__(self, context):
250  Plugin.__init__(self, context)
251  self.setObjectName('SrGuiControllerTuner')
252 
253  self.controller_type = None
254 
255  self._publisher = None
256  self._widget = QWidget()
257 
258  self.file_to_save = None
259 
260  ui_file = os.path.join(rospkg.RosPack().get_path(
261  'sr_gui_controller_tuner'), 'uis', 'SrGuiControllerTuner.ui')
262  loadUi(ui_file, self._widget)
263  self._widget.setObjectName('SrControllerTunerUi')
264  context.add_widget(self._widget)
265 
266  # setting the prefixes
267  self._hand_finder = HandFinder()
268  hand_parameters = self._hand_finder.get_hand_parameters()
269  self._prefix = ""
270  for hand in hand_parameters.mapping:
271  self._widget.select_prefix.addItem(hand_parameters.mapping[hand])
272  if not hand_parameters.mapping:
273  rospy.logerr("No hand detected")
274  QMessageBox.warning(
275  self._widget, "warning", "No hand is detected")
276  else:
277  self._widget.select_prefix.setCurrentIndex(0)
278  self._prefix = hand_parameters.mapping.values()[0]
279 
280  self._widget.select_prefix.currentIndexChanged[
281  'QString'].connect(self.prefix_selected)
282 
283  # stores the movements threads to be able to stop them
284  self.move_threads = []
285 
286  # stores the controllers in the same order as the dropdown
288 
289  # stores a dictionary of the widgets containing the data for
290  # the different controllers.
291  self.ctrl_widgets = {}
292 
293  # a library which helps us doing the real work.
295  os.path.join(
296  rospkg.RosPack().get_path('sr_gui_controller_tuner'),
297  'data', 'controller_settings.xml'))
298 
299  self.sr_controller_tuner_app_.prefix = self._prefix
300  self.sr_controller_tuner_app_.selected_prefix = self._prefix
301  # check the prefix once
302  self.sr_controller_tuner_app_.check_prefix()
303  # refresh the controllers once
305  # attach the button pressed to its action
306  self._widget.btn_refresh_ctrl.pressed.connect(
308  self._widget.dropdown_ctrl.currentIndexChanged.connect(
310 
311  self._widget.btn_save_selected.pressed.connect(
313  self._widget.btn_save_all.pressed.connect(
315  self._widget.btn_select_file_path.pressed.connect(
317 
318  self._widget.btn_set_selected.pressed.connect(
320  self._widget.btn_set_all.pressed.connect(
322 
323  self._widget.btn_load.pressed.connect(self.on_btn_load_clicked_)
324  self._widget.btn_stop_mvts.pressed.connect(
326 
327  self.prefix_selected(self._prefix)
328 
329  def on_btn_plot_pressed_(self, joint_name, btn):
330  plot_thread = PlotThread(btn, joint_name, self.controller_type)
331  plot_thread.start()
332 
333  def on_btn_move_pressed_(self, joint_name, btn):
334  move_thread = MoveThread(btn, joint_name, self.controller_type)
335  move_thread.start()
336  self.move_threads.append(move_thread)
337 
338  def on_changed_controller_type_(self, index=None):
339  """
340  When controller type is changed clear the chosen file path and refresh the tree with the controller settings
341  """
342  if index is None:
343  return
344  self.reset_file_path()
345  if len(self.controllers_in_dropdown) > 0:
347 
348  def reset_file_path(self):
349  """
350  Clear the chosen file path and disable the save button until user selects another path
351  """
352  self._widget.txt_file_path.setText("")
353 
354  self._widget.btn_load.setEnabled(False)
355 
356  # disable the save buttons (until a new file has
357  # been chosen by the user)
358  self._widget.btn_save_all.setEnabled(False)
359  self._widget.btn_save_selected.setEnabled(False)
360 
362  """
363  Perform controller tuning and save settings to user specified file
364  sr_config stack must be installed
365  """
366  path_to_config = "~"
367  try:
368  path_to_config = os.path.join(
369  rospkg.RosPack().get_path('sr_ethercat_hand_config'))
370  except:
371  rospy.logwarn(
372  "couldn't find the sr_ethercat_hand_config package, do you have the sr_config stack installed?")
373 
374  # Reading the param that contains the config_dir suffix that we should use for this hand (e.g.
375  # '' normally for a right hand or 'lh' if this is for a left hand)
376  # the prefix for config dir must use the "checked" prefix, not the
377  # selected one (to handle GUI ns)
378  config_subdir = rospy.get_param(
379  self.sr_controller_tuner_app_.prefix + 'config_dir', '')
380  subpath = "/controls/host/" + config_subdir
381  if self.sr_controller_tuner_app_.edit_only_mode:
382  filter_files = "*.yaml"
383  else:
384  if self.controller_type == "Motor Force":
385  filter_files = "*controllers.yaml"
386  else:
387  if self.sr_controller_tuner_app_.control_mode == "PWM":
388  filter_files = "*s_PWM.yaml"
389  else:
390  filter_files = "*s.yaml"
391 
392  if self.controller_type == "Motor Force":
393  filter_files = "Config (*motor" + filter_files + ")"
394  subpath = "/controls/motors/" + config_subdir
395  elif self.controller_type == "Position":
396  filter_files = "Config (*position_controller" + filter_files + ")"
397  elif self.controller_type == "Muscle Position":
398  filter_files = "Config (*muscle_joint_position_controller" + \
399  filter_files + ")"
400  elif self.controller_type == "Velocity":
401  filter_files = "Config (*velocity_controller" + filter_files + ")"
402  elif self.controller_type == "Mixed Position/Velocity":
403  filter_files = "Config (*position_velocity" + filter_files + ")"
404  elif self.controller_type == "Effort":
405  filter_files = "Config (*effort_controller" + filter_files + ")"
406 
407  path_to_config += subpath
408 
409  filename, _ = QFileDialog.getOpenFileName(
410  self._widget.tree_ctrl_settings, self._widget.tr(
411  'Save Controller Settings'),
412  self._widget.tr(
413  path_to_config),
414  self._widget.tr(filter_files))
415 
416  if filename == "":
417  return
418 
419  self.file_to_save = filename
420 
421  self._widget.txt_file_path.setText(filename)
422 
423  self._widget.btn_load.setEnabled(True)
424 
425  # enable the save buttons once a file has
426  # been chosen
427  self._widget.btn_save_all.setEnabled(True)
428  self._widget.btn_save_selected.setEnabled(True)
429 
431  """
432  reload the parameters in rosparam, then refresh the tree widget
433  """
434  paramlist = rosparam.load_file(self.file_to_save)
435  for params, namespace in paramlist:
436  rosparam.upload_params(namespace, params)
437 
439  self.controllers_in_dropdown[self._widget.dropdown_ctrl.currentIndex()])
440 
442  """
443  Save only the selected controllers
444  """
445  selected_items = self._widget.tree_ctrl_settings.selectedItems()
446 
447  if len(selected_items) == 0:
448  QMessageBox.warning(
449  self._widget.tree_ctrl_settings, "Warning", "No motors selected.")
450 
451  for it in selected_items:
452  if str(it.text(1)) != "":
453  self.save_controller(str(it.text(1)))
454 
456  """
457  Save all controllers
458  """
459  for motor in self.ctrl_widgets.keys():
460  self.save_controller(motor)
461 
463  """
464  Sets the current values for selected controllers using the ros service.
465  """
466  selected_items = self._widget.tree_ctrl_settings.selectedItems()
467 
468  if len(selected_items) == 0:
469  QMessageBox.warning(
470  self._widget.tree_ctrl_settings, "Warning", "No motors selected.")
471 
472  for it in selected_items:
473  if str(it.text(1)) != "":
474  self.set_controller(str(it.text(1)))
475 
477  """
478  Sets the current values for all controllers using the ros service.
479  """
480  for motor in self.ctrl_widgets.keys():
481  self.set_controller(motor)
482 
484  """
485  Calls refresh_controller_tree_ after preparing widgets
486  """
487  ctrls = self.sr_controller_tuner_app_.get_ctrls()
488  self.sr_controller_tuner_app_.refresh_control_mode()
489  self.controllers_in_dropdown = []
490  self._widget.dropdown_ctrl.clear()
491  for ctrl in ctrls:
492  self._widget.dropdown_ctrl.addItem(ctrl)
493  self.controllers_in_dropdown.append(ctrl)
494 
496 
497  def prefix_selected(self, prefix):
498  """
499  Sets the prefix in the controller tuner app and
500  Refreshes the controllers
501  """
502  self._prefix = prefix
503  self.sr_controller_tuner_app_.selected_prefix = self._prefix + "/"
504  self.sr_controller_tuner_app_.check_prefix()
506 
507  def read_settings(self, joint_name):
508  """
509  retrieve settings for joint with given name
510  """
511  dict_of_widgets = self.ctrl_widgets[joint_name]
512 
513  settings = {}
514  for item in dict_of_widgets.items():
515  try:
516  settings[item[0]] = item[1].value()
517  except AttributeError:
518  try:
519  settings[item[0]] = 1 if item[
520  1].checkState() == Qt.Checked else 0
521  except AttributeError:
522  pass
523  return settings
524 
525  def set_controller(self, joint_name):
526  """
527  Sets the current values for the given controller using the ros service.
528  """
529  settings = self.read_settings(joint_name)
530 
531  # uses the library to call the service properly
532  success = self.sr_controller_tuner_app_.set_controller(
533  joint_name, self.controller_type, settings)
534  if success is False:
535  if self.controller_type == "Motor Force":
536  QMessageBox.warning(self._widget.tree_ctrl_settings, "Warning",
537  "Failed to set the PID values for joint " + joint_name +
538  ". This won't work for Gazebo controllers as there are no force controllers yet.")
539  else:
540  QMessageBox.warning(self._widget.tree_ctrl_settings, "Warning",
541  "Failed to set the PID values for joint " + joint_name + ".")
542 
543  def save_controller(self, joint_name):
544  """
545  Saves the current values for the given controller using the ros service.
546  """
547  settings = self.read_settings(joint_name)
548 
549  # uses the library to call the service properly
550  self.sr_controller_tuner_app_.save_controller(
551  joint_name, self.controller_type, settings, self.file_to_save)
552 
553  def refresh_controller_tree_(self, controller_type="Motor Force"):
554  """
555  Get the controller settings and their ranges and display them in the tree.
556  Buttons and plots will be added unless in edit_only mode.
557  Move button will be added if controller is position type
558  Buttons "set all" "set selected" and "stop movements" are disabled in edit_only_mode
559  Controller settings must exist for every motor of every finger in the yaml file.
560  """
561 
562  if self.sr_controller_tuner_app_.edit_only_mode:
563  self._widget.btn_set_selected.setEnabled(False)
564  self._widget.btn_set_all.setEnabled(False)
565  self._widget.btn_stop_mvts.setEnabled(False)
566  else:
567  self._widget.btn_set_selected.setEnabled(True)
568  self._widget.btn_set_all.setEnabled(True)
569  self._widget.btn_stop_mvts.setEnabled(True)
570 
571  self.controller_type = controller_type
572  ctrl_settings = self.sr_controller_tuner_app_.get_controller_settings(
573  controller_type)
574 
575  self._widget.tree_ctrl_settings.clear()
576  self._widget.tree_ctrl_settings.setColumnCount(
577  ctrl_settings.nb_columns)
578  # clear the ctrl_widgets as the motor name might change also now
579  self.ctrl_widgets = {}
580 
581  tmp_headers = []
582  for header in ctrl_settings.headers:
583  tmp_headers.append(header["name"])
584  self._widget.tree_ctrl_settings.setHeaderLabels(tmp_headers)
585 
586  hand_item = QTreeWidgetItem(ctrl_settings.hand_item)
587  self._widget.tree_ctrl_settings.addTopLevelItem(hand_item)
588  for index_finger, finger_settings in enumerate(ctrl_settings.fingers):
589  finger_item = QTreeWidgetItem(hand_item, finger_settings)
590  self._widget.tree_ctrl_settings.addTopLevelItem(finger_item)
591  for motor_settings in ctrl_settings.motors[index_finger]:
592  motor_name = motor_settings[1]
593 
594  motor_item = QTreeWidgetItem(finger_item, motor_settings)
595  self._widget.tree_ctrl_settings.addTopLevelItem(motor_item)
596 
597  parameter_values = self.sr_controller_tuner_app_.load_parameters(
598  controller_type, motor_name)
599 
600  if parameter_values != -1:
601  # the parameters have been found
602  self.ctrl_widgets[motor_name] = {}
603 
604  # buttons for plot/move are not added in edit_only_mode
605  if not self.sr_controller_tuner_app_.edit_only_mode:
606  # add buttons for the automatic procedures (plot / move
607  # / ...)
608  frame_buttons = QFrame()
609  layout_buttons = QHBoxLayout()
610  btn_plot = QPushButton("Plot")
611  self.ctrl_widgets[motor_name]["btn_plot"] = btn_plot
612  self.ctrl_widgets[
613  motor_name][
614  "btn_plot"].clicked.connect(partial(self.on_btn_plot_pressed_,
615  motor_name, self.ctrl_widgets[motor_name]["btn_plot"]))
616  layout_buttons.addWidget(btn_plot)
617 
618  if self.controller_type in ["Position", "Muscle Position", "Mixed Position/Velocity"]:
619  # only adding Move button for position controllers
620  btn_move = QPushButton("Move")
621  self.ctrl_widgets[motor_name][
622  "btn_move"] = btn_move
623  self.ctrl_widgets[
624  motor_name][
625  "btn_move"].clicked.connect(partial(self.on_btn_move_pressed_, motor_name,
626  self.ctrl_widgets[motor_name]["btn_move"]))
627  layout_buttons.addWidget(btn_move)
628  frame_buttons.setLayout(layout_buttons)
629 
630  self._widget.tree_ctrl_settings.setItemWidget(
631  motor_item, 0, frame_buttons)
632 
633  for index_item, item in enumerate(ctrl_settings.headers):
634  param_name = item["name"].lower()
635  if param_name not in parameter_values:
636  rospy.logdebug("Param %s not found for joint %s" % (param_name, motor_name))
637  continue
638 
639  if item["type"] == "Bool":
640  check_box = QCheckBox()
641 
642  param_val = parameter_values[param_name]
643  check_box.setChecked(param_val)
644  if param_name == "sign":
645  check_box.setToolTip("Check if you want a negative sign\n"
646  "(if the motor is being driven\n the wrong way around).")
647 
648  self._widget.tree_ctrl_settings.setItemWidget(
649  motor_item, index_item, check_box)
650 
651  self.ctrl_widgets[motor_name][
652  param_name] = check_box
653 
654  if item["type"] == "Int":
655  spin_box = QSpinBox()
656  spin_box.setRange(
657  int(item["min"]), int(item["max"]))
658  spin_box.setValue(
659  int(parameter_values[param_name]))
660  self.ctrl_widgets[motor_name][
661  param_name] = spin_box
662 
663  self._widget.tree_ctrl_settings.setItemWidget(
664  motor_item, index_item, spin_box)
665 
666  if item["type"] == "Float":
667  spin_box = QDoubleSpinBox()
668  spin_box.setRange(-65535.0, 65535.0)
669  spin_box.setDecimals(3)
670 
671  spin_box.setValue(
672  float(parameter_values[param_name]))
673  self.ctrl_widgets[motor_name][
674  param_name] = spin_box
675 
676  self._widget.tree_ctrl_settings.setItemWidget(
677  motor_item, index_item, spin_box)
678 
679  motor_item.setExpanded(True)
680  else:
681  motor_item.setText(
682  1, "parameters not found - controller tuning disabled")
683  finger_item.setExpanded(True)
684  hand_item.setExpanded(True)
685 
686  for col in range(0, self._widget.tree_ctrl_settings.columnCount()):
687  self._widget.tree_ctrl_settings.resizeColumnToContents(col)
688 
690  for move_thread in self.move_threads:
691  move_thread.__del__()
692  self.move_threads = []
693 
694  #
695  # Default methods for the rosgui plugins
696 
698  if self._publisher is not None:
699  self._publisher.unregister()
700  self._publisher = None
701 
702  def shutdown_plugin(self):
703  self._unregisterPublisher()
704 
705  def save_settings(self, global_settings, perspective_settings):
706  pass
707 
708  def restore_settings(self, global_settings, perspective_settings):
709  pass
def restore_settings(self, global_settings, perspective_settings)
def __init__(self, parent=None, joint_name="FFJ0", controller_type="Motor Force")
def refresh_controller_tree_(self, controller_type="Motor Force")
def save_settings(self, global_settings, perspective_settings)
def __init__(self, parent=None, joint_name="FFJ0", controller_type="Motor Force")


sr_gui_controller_tuner
Author(s): Ugo Cupcic
autogenerated on Wed Oct 14 2020 03:22:49