controller_tuner.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2011 Shadow Robot Company Ltd.
00004 #
00005 # This program is free software: you can redistribute it and/or modify it
00006 # under the terms of the GNU General Public License as published by the Free
00007 # Software Foundation, either version 2 of the License, or (at your option)
00008 # any later version.
00009 #
00010 # This program is distributed in the hope that it will be useful, but WITHOUT
00011 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00012 # FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
00013 # more details.
00014 #
00015 # You should have received a copy of the GNU General Public License along
00016 # with this program.  If not, see <http://www.gnu.org/licenses/>.
00017 #
00018 
00019 import os
00020 import subprocess
00021 import math
00022 import time
00023 import rospy
00024 import rosparam
00025 import rospkg
00026 
00027 from qt_gui.plugin import Plugin
00028 from python_qt_binding import loadUi
00029 
00030 from QtCore import Qt, QThread
00031 from QtGui import QWidget, QTreeWidgetItem, QCheckBox, QSpinBox, QDoubleSpinBox
00032 from QtGui import QFileDialog, QMessageBox, QPushButton, QFrame, QHBoxLayout
00033 from functools import partial
00034 from tempfile import NamedTemporaryFile
00035 
00036 from sensor_msgs.msg import JointState
00037 
00038 from sr_gui_controller_tuner.sr_controller_tuner import SrControllerTunerApp
00039 from sr_utilities.hand_finder import HandFinder
00040 
00041 
00042 class PlotThread(QThread):
00043 
00044     def __init__(self, parent=None, joint_name="FFJ0", controller_type="Motor Force"):
00045         QThread.__init__(self, parent)
00046         self.joint_name_ = joint_name
00047         self.is_joint_0_ = False
00048         self.joint_index_in_joint_state_ = None
00049         try:
00050             self.joint_index_in_joint_state_ = [
00051                 "FFJ0", "MFJ0", "RFJ0", "LFJ0"].index(self.joint_name_)
00052             self.is_joint_0_ = True
00053         except ValueError:
00054             self.is_joint_0_ = False
00055 
00056         self.controller_type_ = controller_type
00057 
00058         # prepares the title for the plot (can't contain spaces)
00059         self.plot_title_ = self.joint_name_ + " " + self.controller_type_
00060         self.plot_title_ = self.plot_title_.replace(" ", "_").replace("/", "_")
00061 
00062         # stores the subprocesses to be able to terminate them on close
00063         self.subprocess_ = []
00064 
00065     def run(self):
00066         """
00067         Creates an appropriate plot according to controller type
00068         Also creates a subscription if controller is of Motor Force type
00069         """
00070         # rxplot_str = "rxplot -b 30 -p 30 --title=" + self.plot_title_ + " "
00071         rxplot_str = "rosrun rqt_plot rqt_plot "
00072 
00073         if self.controller_type_ == "Motor Force":
00074             # the joint 0s are published on a different topic:
00075             # /joint_0s/joint_states
00076             if not self.is_joint_0_:
00077                 # subscribe to joint_states to get the index of the joint in
00078                 # the message
00079                 self.subscriber_ = rospy.Subscriber(
00080                     "joint_states", JointState, self.js_callback_)
00081 
00082                 # wait until we got the joint index in the joint
00083                 # states message
00084                 while self.joint_index_in_joint_state_ is None:
00085                     time.sleep(0.01)
00086 
00087                 rxplot_str += "joint_states/effort[" + str(
00088                     self.joint_index_in_joint_state_) + "]"
00089             else:
00090                 rxplot_str += "joint_0s/joint_states/effort[" + str(
00091                     self.joint_index_in_joint_state_) + "]"
00092 
00093         elif self.controller_type_ == "Position":
00094             rxplot_str += "sh_" + self.joint_name_.lower() + "_position_controller/state/set_point,sh_" + \
00095                           self.joint_name_.lower() + "_position_controller/state/process_value sh_" + \
00096                           self.joint_name_.lower() + "_position_controller/state/command"
00097         elif self.controller_type_ == "Muscle Position":
00098             rxplot_str += "sh_" + self.joint_name_.lower() + "_muscle_position_controller/state/set_point,sh_" + \
00099                           self.joint_name_.lower() + "_muscle_position_controller/state/process_value sh_" + \
00100                           self.joint_name_.lower() + "_muscle_position_controller/state/pseudo_command sh_" + \
00101                           self.joint_name_.lower() + "_muscle_position_controller/state/valve_muscle_0,sh_" + \
00102                           self.joint_name_.lower() + "_muscle_position_controller/state/valve_muscle_1"
00103         elif self.controller_type_ == "Velocity":
00104             rxplot_str += "sh_" + self.joint_name_.lower() + "_velocity_controller/state/set_point,sh_" + \
00105                           self.joint_name_.lower() + "_velocity_controller/state/process_value"
00106         elif self.controller_type_ == "Mixed Position/Velocity":
00107             rxplot_str += "sh_" + \
00108                           self.joint_name_.lower() + "_mixed_position_velocity_controller/state/set_point,sh_" + \
00109                           self.joint_name_.lower() + "_mixed_position_velocity_controller/state/process_value sh_" + \
00110                           self.joint_name_.lower() + "_mixed_position_velocity_controller/state/process_value_dot," + \
00111                           "sh_" + \
00112                           self.joint_name_.lower() + \
00113                           "_mixed_position_velocity_controller/state/commanded_velocity " + \
00114                           "sh_" + \
00115                           self.joint_name_.lower() + "_mixed_position_velocity_controller/state/command,sh_" + \
00116                           self.joint_name_.lower() + \
00117                           "_mixed_position_velocity_controller/state/measured_effort,sh_" + \
00118                           self.joint_name_.lower() + "_mixed_position_velocity_controller/state/friction_compensation"
00119         elif self.controller_type_ == "Effort":
00120             rxplot_str += "sh_" + self.joint_name_.lower() + "_effort_controller/state/set_point,sh_" + \
00121                           self.joint_name_.lower() + "_effort_controller/state/process_value"
00122 
00123         self.subprocess_.append(subprocess.Popen(rxplot_str.split()))
00124 
00125     def js_callback_(self, msg):
00126         # get the joint index once, then unregister
00127         self.joint_index_in_joint_state_ = msg.name.index(
00128             self.joint_name_.upper())
00129         self.subscriber_.unregister()
00130         self.subscriber_ = None
00131 
00132     def __del__(self):
00133         for subprocess in self.subprocess_:
00134             # killing the rxplot to close the window
00135             subprocess.kill()
00136 
00137         if self.subscriber_ is not None:
00138             self.subscriber_.unregister()
00139             self.subscriber_ = None
00140 
00141         self.wait()
00142 
00143 
00144 class MoveThread(QThread):
00145 
00146     def __init__(self, parent=None, joint_name="FFJ0", controller_type="Motor Force"):
00147         QThread.__init__(self, parent)
00148         self.joint_name_ = joint_name
00149         self.controller_type_ = controller_type
00150         self.btn = parent
00151         self.subprocess_ = []
00152 
00153     def run(self):
00154         self.launch_()
00155 
00156     def __del__(self):
00157         for subprocess in self.subprocess_:
00158             subprocess.terminate()
00159         self.wait()
00160 
00161     def create_launch_file_(self):
00162         """
00163         Create a launch file dynamically
00164         """
00165         # Not using automatic move for velocity and effort controllers
00166         controller_name_ = ""
00167         message_type = "ros"
00168         if self.controller_type_ == "Position":
00169             controller_name_ = "sh_" + \
00170                 self.joint_name_.lower() + "_position_controller"
00171         if self.controller_type_ == "Muscle Position":
00172             controller_name_ = "sh_" + \
00173                 self.joint_name_.lower() + "_muscle_position_controller"
00174         elif self.controller_type_ == "Mixed Position/Velocity":
00175             controller_name_ = "sh_" + \
00176                 self.joint_name_.lower() + \
00177                 "_mixed_position_velocity_controller"
00178             message_type = "sr"
00179 
00180         min_max = self.get_min_max_()
00181         namespace = rospy.get_namespace()
00182 
00183         string = "<launch> <node ns=\"" + namespace + \
00184             "\" pkg=\"sr_movements\" name=\"sr_movements\" type=\"sr_movements\">"
00185         string += "<remap from=\"~targets\" to=\"" + \
00186             controller_name_ + "/command\"/>"
00187         string += "<remap from=\"~inputs\" to=\"" + \
00188             controller_name_ + "/state\"/>"
00189         string += "<param name=\"image_path\" value=\"$(find sr_movements)/movements/test.png\"/>"
00190         string += "<param name=\"min\" value=\"" + str(min_max[0]) + "\"/>"
00191         string += "<param name=\"max\" value=\"" + str(min_max[1]) + "\"/>"
00192         string += "<param name=\"publish_rate\" value=\"100\"/>"
00193         string += "<param name=\"repetition\" value=\"1000\"/>"
00194         string += "<param name=\"nb_step\" value=\"10000\"/>"
00195         string += "<param name=\"msg_type\" value=\"{}\"/>".format(
00196             message_type)
00197         string += "</node> </launch>"
00198         tmp_launch_file = NamedTemporaryFile(delete=False)
00199 
00200         tmp_launch_file.writelines(string)
00201         tmp_launch_file.close()
00202 
00203         return tmp_launch_file.name
00204 
00205     def get_min_max_(self):
00206         """
00207         Retrieve joint limits in radians for joint in self.joint_name
00208         """
00209         # assuming 4 character joint names at the end and trimming any prefix
00210         # TODO: Shouldn't this be read from the URDF ?
00211         joint_name = self.joint_name_[-4:]
00212         if joint_name in ["FFJ0", "MFJ0", "RFJ0", "LFJ0"]:
00213             return [0.0, math.radians(180.0)]
00214         elif joint_name in ["FFJ3", "MFJ3", "RFJ3", "LFJ3", "THJ1"]:
00215             return [0.0, math.radians(90.0)]
00216         elif joint_name in ["LFJ5"]:
00217             return [0.0, math.radians(45.0)]
00218         elif joint_name in ["FFJ4", "MFJ4", "RFJ4", "LFJ4"]:
00219             return [math.radians(-20.0), math.radians(20.0)]
00220         elif joint_name in ["THJ2"]:
00221             return [math.radians(-40.0), math.radians(40.0)]
00222         elif joint_name in ["THJ3"]:
00223             return [math.radians(-15.0), math.radians(15.0)]
00224         elif joint_name in ["THJ4"]:
00225             return [math.radians(0.0), math.radians(70.0)]
00226         elif joint_name in ["THJ5"]:
00227             return [math.radians(-60.0), math.radians(60.0)]
00228         elif joint_name in ["WRJ1"]:
00229             return [math.radians(-30.0), math.radians(45.0)]
00230         elif joint_name in ["WRJ2"]:
00231             return [math.radians(-30.0), math.radians(10.0)]
00232 
00233     def launch_(self):
00234         """
00235         launch a dynamically created launch file
00236         """
00237         filename = self.create_launch_file_()
00238 
00239         launch_string = "roslaunch " + filename
00240 
00241         self.subprocess_.append(subprocess.Popen(launch_string.split()))
00242 
00243 
00244 class SrGuiControllerTuner(Plugin):
00245 
00246     """
00247     a rosgui plugin for tuning the sr_mechanism_controllers
00248     """
00249 
00250     def __init__(self, context):
00251         Plugin.__init__(self, context)
00252         self.setObjectName('SrGuiControllerTuner')
00253 
00254         self.controller_type = None
00255 
00256         self._publisher = None
00257         self._widget = QWidget()
00258 
00259         self.file_to_save = None
00260 
00261         ui_file = os.path.join(rospkg.RosPack().get_path(
00262             'sr_gui_controller_tuner'), 'uis', 'SrGuiControllerTuner.ui')
00263         loadUi(ui_file, self._widget)
00264         self._widget.setObjectName('SrControllerTunerUi')
00265         context.add_widget(self._widget)
00266 
00267         # setting the prefixes
00268         self._hand_finder = HandFinder()
00269         hand_parameters = self._hand_finder.get_hand_parameters()
00270         self._prefix = ""
00271         for hand in hand_parameters.mapping:
00272             self._widget.select_prefix.addItem(hand_parameters.mapping[hand])
00273         if not hand_parameters.mapping:
00274             rospy.logerr("No hand detected")
00275             QMessageBox.warning(
00276                 self._widget, "warning", "No hand is detected")
00277         else:
00278             self._widget.select_prefix.setCurrentIndex(0)
00279             self._prefix = hand_parameters.mapping.values()[0]
00280 
00281             self._widget.select_prefix.currentIndexChanged[
00282                 'QString'].connect(self.prefix_selected)
00283 
00284             # stores the movements threads to be able to stop them
00285             self.move_threads = []
00286 
00287             # stores the controllers in the same order as the dropdown
00288             self.controllers_in_dropdown = []
00289 
00290             # stores a dictionary of the widgets containing the data for
00291             # the different controllers.
00292             self.ctrl_widgets = {}
00293 
00294             # a library which helps us doing the real work.
00295             self.sr_controller_tuner_app_ = SrControllerTunerApp(
00296                 os.path.join(
00297                     rospkg.RosPack().get_path('sr_gui_controller_tuner'),
00298                     'data', 'controller_settings.xml'))
00299 
00300             self.sr_controller_tuner_app_.prefix = self._prefix
00301             self.sr_controller_tuner_app_.selected_prefix = self._prefix
00302             # check the prefix once
00303             self.sr_controller_tuner_app_.check_prefix()
00304             # refresh the controllers once
00305             self.on_btn_refresh_ctrl_clicked_()
00306             # attach the button pressed to its action
00307             self._widget.btn_refresh_ctrl.pressed.connect(
00308                 self.on_btn_refresh_ctrl_clicked_)
00309             self._widget.dropdown_ctrl.currentIndexChanged.connect(
00310                 self.on_changed_controller_type_)
00311 
00312             self._widget.btn_save_selected.pressed.connect(
00313                 self.on_btn_save_selected_clicked_)
00314             self._widget.btn_save_all.pressed.connect(
00315                 self.on_btn_save_all_clicked_)
00316             self._widget.btn_select_file_path.pressed.connect(
00317                 self.on_btn_select_file_path_clicked_)
00318 
00319             self._widget.btn_set_selected.pressed.connect(
00320                 self.on_btn_set_selected_clicked_)
00321             self._widget.btn_set_all.pressed.connect(
00322                 self.on_btn_set_all_clicked_)
00323 
00324             self._widget.btn_load.pressed.connect(self.on_btn_load_clicked_)
00325             self._widget.btn_stop_mvts.pressed.connect(
00326                 self.on_btn_stop_mvts_clicked_)
00327 
00328             self.prefix_selected(self._prefix)
00329 
00330     def on_btn_plot_pressed_(self, joint_name, btn):
00331         plot_thread = PlotThread(btn, joint_name, self.controller_type)
00332         plot_thread.start()
00333 
00334     def on_btn_move_pressed_(self, joint_name, btn):
00335         move_thread = MoveThread(btn, joint_name, self.controller_type)
00336         move_thread.start()
00337         self.move_threads.append(move_thread)
00338 
00339     def on_changed_controller_type_(self, index=None):
00340         """
00341         When controller type is changed clear the chosen file path and refresh the tree with the controller settings
00342         """
00343         if index is None:
00344             return
00345         self.reset_file_path()
00346         if len(self.controllers_in_dropdown) > 0:
00347             self.refresh_controller_tree_(self.controllers_in_dropdown[index])
00348 
00349     def reset_file_path(self):
00350         """
00351         Clear the chosen file path and disable the save button until user selects another path
00352         """
00353         self._widget.txt_file_path.setText("")
00354 
00355         self._widget.btn_load.setEnabled(False)
00356 
00357         # disable the save buttons (until a new file has
00358         # been chosen by the user)
00359         self._widget.btn_save_all.setEnabled(False)
00360         self._widget.btn_save_selected.setEnabled(False)
00361 
00362     def on_btn_select_file_path_clicked_(self):
00363         """
00364         Perform controller tuning and save settings to user specified file
00365         sr_config stack must be installed
00366         """
00367         path_to_config = "~"
00368         try:
00369             path_to_config = os.path.join(
00370                 rospkg.RosPack().get_path('sr_ethercat_hand_config'))
00371         except:
00372             rospy.logwarn(
00373                 "couldn't find the sr_ethercat_hand_config package, do you have the sr_config stack installed?")
00374 
00375         # Reading the param that contains the config_dir suffix that we should use for this hand (e.g.
00376         # '' normally for a right hand  or 'lh' if this is for a left hand)
00377         # the prefix for config dir must use the "checked" prefix, not the
00378         # selected one (to handle GUI ns)
00379         config_subdir = rospy.get_param(
00380             self.sr_controller_tuner_app_.prefix + 'config_dir', '')
00381         subpath = "/controls/host/" + config_subdir
00382         if self.sr_controller_tuner_app_.edit_only_mode:
00383             filter_files = "*.yaml"
00384         else:
00385             if self.controller_type == "Motor Force":
00386                 filter_files = "*controllers.yaml"
00387             else:
00388                 if self.sr_controller_tuner_app_.control_mode == "PWM":
00389                     filter_files = "*s_PWM.yaml"
00390                 else:
00391                     filter_files = "*s.yaml"
00392 
00393         if self.controller_type == "Motor Force":
00394             filter_files = "Config (*motor" + filter_files + ")"
00395             subpath = "/controls/motors/" + config_subdir
00396         elif self.controller_type == "Position":
00397             filter_files = "Config (*position_controller" + filter_files + ")"
00398         elif self.controller_type == "Muscle Position":
00399             filter_files = "Config (*muscle_joint_position_controller" + \
00400                 filter_files + ")"
00401         elif self.controller_type == "Velocity":
00402             filter_files = "Config (*velocity_controller" + filter_files + ")"
00403         elif self.controller_type == "Mixed Position/Velocity":
00404             filter_files = "Config (*position_velocity" + filter_files + ")"
00405         elif self.controller_type == "Effort":
00406             filter_files = "Config (*effort_controller" + filter_files + ")"
00407 
00408         path_to_config += subpath
00409 
00410         filename, _ = QFileDialog.getOpenFileName(
00411             self._widget.tree_ctrl_settings, self._widget.tr(
00412                 'Save Controller Settings'),
00413             self._widget.tr(
00414                 path_to_config),
00415             self._widget.tr(filter_files))
00416 
00417         if filename == "":
00418             return
00419 
00420         self.file_to_save = filename
00421 
00422         self._widget.txt_file_path.setText(filename)
00423 
00424         self._widget.btn_load.setEnabled(True)
00425 
00426         # enable the save buttons once a file has
00427         # been chosen
00428         self._widget.btn_save_all.setEnabled(True)
00429         self._widget.btn_save_selected.setEnabled(True)
00430 
00431     def on_btn_load_clicked_(self):
00432         """
00433         reload the parameters in rosparam, then refresh the tree widget
00434         """
00435         paramlist = rosparam.load_file(self.file_to_save)
00436         for params, namespace in paramlist:
00437             rosparam.upload_params(namespace, params)
00438 
00439         self.refresh_controller_tree_(
00440             self.controllers_in_dropdown[self._widget.dropdown_ctrl.currentIndex()])
00441 
00442     def on_btn_save_selected_clicked_(self):
00443         """
00444         Save only the selected controllers
00445         """
00446         selected_items = self._widget.tree_ctrl_settings.selectedItems()
00447 
00448         if len(selected_items) == 0:
00449             QMessageBox.warning(
00450                 self._widget.tree_ctrl_settings, "Warning", "No motors selected.")
00451 
00452         for it in selected_items:
00453             if str(it.text(1)) != "":
00454                 self.save_controller(str(it.text(1)))
00455 
00456     def on_btn_save_all_clicked_(self):
00457         """
00458         Save all controllers
00459         """
00460         for motor in self.ctrl_widgets.keys():
00461             self.save_controller(motor)
00462 
00463     def on_btn_set_selected_clicked_(self):
00464         """
00465         Sets the current values for selected controllers using the ros service.
00466         """
00467         selected_items = self._widget.tree_ctrl_settings.selectedItems()
00468 
00469         if len(selected_items) == 0:
00470             QMessageBox.warning(
00471                 self._widget.tree_ctrl_settings, "Warning", "No motors selected.")
00472 
00473         for it in selected_items:
00474             if str(it.text(1)) != "":
00475                 self.set_controller(str(it.text(1)))
00476 
00477     def on_btn_set_all_clicked_(self):
00478         """
00479         Sets the current values for all controllers using the ros service.
00480         """
00481         for motor in self.ctrl_widgets.keys():
00482             self.set_controller(motor)
00483 
00484     def on_btn_refresh_ctrl_clicked_(self):
00485         """
00486         Calls refresh_controller_tree_ after preparing widgets
00487         """
00488         ctrls = self.sr_controller_tuner_app_.get_ctrls()
00489         self.sr_controller_tuner_app_.refresh_control_mode()
00490         self.controllers_in_dropdown = []
00491         self._widget.dropdown_ctrl.clear()
00492         for ctrl in ctrls:
00493             self._widget.dropdown_ctrl.addItem(ctrl)
00494             self.controllers_in_dropdown.append(ctrl)
00495 
00496         self.refresh_controller_tree_()
00497 
00498     def prefix_selected(self, prefix):
00499         """
00500         Sets the prefix in the controller tuner app and
00501         Refreshes the controllers
00502         """
00503         self._prefix = prefix
00504         self.sr_controller_tuner_app_.selected_prefix = self._prefix + "/"
00505         self.sr_controller_tuner_app_.check_prefix()
00506         self.on_btn_refresh_ctrl_clicked_()
00507 
00508     def read_settings(self, joint_name):
00509         """
00510         retrieve settings for joint with given name
00511         """
00512         dict_of_widgets = self.ctrl_widgets[joint_name]
00513 
00514         settings = {}
00515         for item in dict_of_widgets.items():
00516             try:
00517                 settings[item[0]] = item[1].value()
00518             except AttributeError:
00519                 try:
00520                     settings[item[0]] = 1 if item[
00521                         1].checkState() == Qt.Checked else 0
00522                 except AttributeError:
00523                     pass
00524         return settings
00525 
00526     def set_controller(self, joint_name):
00527         """
00528         Sets the current values for the given controller using the ros service.
00529         """
00530         settings = self.read_settings(joint_name)
00531 
00532         # uses the library to call the service properly
00533         success = self.sr_controller_tuner_app_.set_controller(
00534             joint_name, self.controller_type, settings)
00535         if success is False:
00536             if self.controller_type == "Motor Force":
00537                 QMessageBox.warning(self._widget.tree_ctrl_settings, "Warning",
00538                                     "Failed to set the PID values for joint " + joint_name +
00539                                     ". This won't work for Gazebo controllers as there are no force controllers yet.")
00540             else:
00541                 QMessageBox.warning(self._widget.tree_ctrl_settings, "Warning",
00542                                     "Failed to set the PID values for joint " + joint_name + ".")
00543 
00544     def save_controller(self, joint_name):
00545         """
00546         Saves the current values for the given controller using the ros service.
00547         """
00548         settings = self.read_settings(joint_name)
00549 
00550         # uses the library to call the service properly
00551         self.sr_controller_tuner_app_.save_controller(
00552             joint_name, self.controller_type, settings, self.file_to_save)
00553 
00554     def refresh_controller_tree_(self, controller_type="Motor Force"):
00555         """
00556         Get the controller settings and their ranges and display them in the tree.
00557         Buttons and plots will be added unless in edit_only mode.
00558         Move button will be added if controller is position type
00559         Buttons "set all" "set selected" and "stop movements" are disabled in edit_only_mode
00560         Controller settings must exist for every motor of every finger in the yaml file.
00561         """
00562 
00563         if self.sr_controller_tuner_app_.edit_only_mode:
00564             self._widget.btn_set_selected.setEnabled(False)
00565             self._widget.btn_set_all.setEnabled(False)
00566             self._widget.btn_stop_mvts.setEnabled(False)
00567         else:
00568             self._widget.btn_set_selected.setEnabled(True)
00569             self._widget.btn_set_all.setEnabled(True)
00570             self._widget.btn_stop_mvts.setEnabled(True)
00571 
00572         self.controller_type = controller_type
00573         ctrl_settings = self.sr_controller_tuner_app_.get_controller_settings(
00574             controller_type)
00575 
00576         self._widget.tree_ctrl_settings.clear()
00577         self._widget.tree_ctrl_settings.setColumnCount(
00578             ctrl_settings.nb_columns)
00579         # clear the ctrl_widgets as the motor name might change also now
00580         self.ctrl_widgets = {}
00581 
00582         tmp_headers = []
00583         for header in ctrl_settings.headers:
00584             tmp_headers.append(header["name"])
00585         self._widget.tree_ctrl_settings.setHeaderLabels(tmp_headers)
00586 
00587         hand_item = QTreeWidgetItem(ctrl_settings.hand_item)
00588         self._widget.tree_ctrl_settings.addTopLevelItem(hand_item)
00589         for index_finger, finger_settings in enumerate(ctrl_settings.fingers):
00590             finger_item = QTreeWidgetItem(hand_item, finger_settings)
00591             self._widget.tree_ctrl_settings.addTopLevelItem(finger_item)
00592             for motor_settings in ctrl_settings.motors[index_finger]:
00593                 motor_name = motor_settings[1]
00594 
00595                 motor_item = QTreeWidgetItem(finger_item, motor_settings)
00596                 self._widget.tree_ctrl_settings.addTopLevelItem(motor_item)
00597 
00598                 parameter_values = self.sr_controller_tuner_app_.load_parameters(
00599                     controller_type, motor_name)
00600                 if parameter_values != -1:
00601                     # the parameters have been found
00602                     self.ctrl_widgets[motor_name] = {}
00603 
00604                     # buttons for plot/move are not added in edit_only_mode
00605                     if not self.sr_controller_tuner_app_.edit_only_mode:
00606                         # add buttons for the automatic procedures (plot / move
00607                         # / ...)
00608                         frame_buttons = QFrame()
00609                         layout_buttons = QHBoxLayout()
00610                         btn_plot = QPushButton("Plot")
00611                         self.ctrl_widgets[motor_name]["btn_plot"] = btn_plot
00612                         self.ctrl_widgets[
00613                             motor_name][
00614                             "btn_plot"].clicked.connect(partial(self.on_btn_plot_pressed_,
00615                                                                 motor_name, self.ctrl_widgets[motor_name]["btn_plot"]))
00616                         layout_buttons.addWidget(btn_plot)
00617 
00618                         if self.controller_type in ["Position", "Muscle Position", "Mixed Position/Velocity"]:
00619                             # only adding Move button for position controllers
00620                             btn_move = QPushButton("Move")
00621                             self.ctrl_widgets[motor_name][
00622                                 "btn_move"] = btn_move
00623                             self.ctrl_widgets[
00624                                 motor_name][
00625                                 "btn_move"].clicked.connect(partial(self.on_btn_move_pressed_, motor_name,
00626                                                                     self.ctrl_widgets[motor_name]["btn_move"]))
00627                             layout_buttons.addWidget(btn_move)
00628                             frame_buttons.setLayout(layout_buttons)
00629 
00630                         self._widget.tree_ctrl_settings.setItemWidget(
00631                             motor_item, 0, frame_buttons)
00632 
00633                     for index_item, item in enumerate(ctrl_settings.headers):
00634                         if item["type"] == "Bool":
00635                             check_box = QCheckBox()
00636 
00637                             param_name = item["name"].lower()
00638                             param_val = parameter_values[param_name]
00639                             check_box.setChecked(param_val)
00640                             if param_name == "sign":
00641                                 check_box.setToolTip("Check if you want a negative sign\n"
00642                                                      "(if the motor is being driven\n the wrong way around).")
00643 
00644                             self._widget.tree_ctrl_settings.setItemWidget(
00645                                 motor_item, index_item, check_box)
00646 
00647                             self.ctrl_widgets[motor_name][
00648                                 param_name] = check_box
00649 
00650                         if item["type"] == "Int":
00651                             spin_box = QSpinBox()
00652                             spin_box.setRange(
00653                                 int(item["min"]), int(item["max"]))
00654 
00655                             param_name = item["name"].lower()
00656                             spin_box.setValue(
00657                                 int(parameter_values[param_name]))
00658                             self.ctrl_widgets[motor_name][
00659                                 param_name] = spin_box
00660 
00661                             self._widget.tree_ctrl_settings.setItemWidget(
00662                                 motor_item, index_item, spin_box)
00663 
00664                         if item["type"] == "Float":
00665                             spin_box = QDoubleSpinBox()
00666                             spin_box.setRange(-65535.0, 65535.0)
00667                             spin_box.setDecimals(3)
00668 
00669                             param_name = item["name"].lower()
00670                             spin_box.setValue(
00671                                 float(parameter_values[param_name]))
00672                             self.ctrl_widgets[motor_name][
00673                                 param_name] = spin_box
00674 
00675                             self._widget.tree_ctrl_settings.setItemWidget(
00676                                 motor_item, index_item, spin_box)
00677 
00678                         motor_item.setExpanded(True)
00679                 else:
00680                     motor_item.setText(
00681                         1, "parameters not found - controller tuning disabled")
00682             finger_item.setExpanded(True)
00683         hand_item.setExpanded(True)
00684 
00685         for col in range(0, self._widget.tree_ctrl_settings.columnCount()):
00686             self._widget.tree_ctrl_settings.resizeColumnToContents(col)
00687 
00688     def on_btn_stop_mvts_clicked_(self):
00689         for move_thread in self.move_threads:
00690             move_thread.__del__()
00691         self.move_threads = []
00692 
00693     #
00694     # Default methods for the rosgui plugins
00695 
00696     def _unregisterPublisher(self):
00697         if self._publisher is not None:
00698             self._publisher.unregister()
00699             self._publisher = None
00700 
00701     def shutdown_plugin(self):
00702         self._unregisterPublisher()
00703 
00704     def save_settings(self, global_settings, perspective_settings):
00705         pass
00706 
00707     def restore_settings(self, global_settings, perspective_settings):
00708         pass


sr_gui_controller_tuner
Author(s): Ugo Cupcic
autogenerated on Thu Jun 6 2019 21:13:52