27 from python_qt_binding
import loadUi
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
35 from sensor_msgs.msg
import JointState
38 from sr_utilities.hand_finder
import HandFinder
43 def __init__(self, parent=None, joint_name="FFJ0", controller_type="Motor Force"):
44 QThread.__init__(self, parent)
50 "FFJ0",
"MFJ0",
"RFJ0",
"LFJ0"].index(self.
joint_name_)
59 self.
plot_title_ = self.plot_title_.replace(
" ",
"_").replace(
"/",
"_")
66 Creates an appropriate plot according to controller type 67 Also creates a subscription if controller is of Motor Force type 70 rxplot_str =
"rosrun rqt_plot rqt_plot " 86 rxplot_str +=
"joint_states/effort[" + str(
89 rxplot_str +=
"joint_0s/joint_states/effort[" + str(
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" 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" 103 rxplot_str +=
"sh_" + self.joint_name_.lower() +
"_velocity_controller/state/set_point,sh_" + \
104 self.joint_name_.lower() +
"_velocity_controller/state/process_value" 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," + \
111 self.joint_name_.lower() + \
112 "_mixed_position_velocity_controller/state/commanded_velocity " + \
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" 119 rxplot_str +=
"sh_" + self.joint_name_.lower() +
"_effort_controller/state/set_point,sh_" + \
120 self.joint_name_.lower() +
"_effort_controller/state/process_value" 122 self.subprocess_.append(subprocess.Popen(rxplot_str.split()))
127 self.joint_name_.upper())
128 self.subscriber_.unregister()
137 self.subscriber_.unregister()
145 def __init__(self, parent=None, joint_name="FFJ0", controller_type="Motor Force"):
146 QThread.__init__(self, parent)
157 subprocess.terminate()
162 Create a launch file dynamically 165 controller_name_ =
"" 168 controller_name_ =
"sh_" + \
169 self.joint_name_.lower() +
"_position_controller" 171 controller_name_ =
"sh_" + \
172 self.joint_name_.lower() +
"_muscle_position_controller" 174 controller_name_ =
"sh_" + \
175 self.joint_name_.lower() + \
176 "_mixed_position_velocity_controller" 180 namespace = rospy.get_namespace()
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(
196 string +=
"</node> </launch>" 197 tmp_launch_file = NamedTemporaryFile(delete=
False)
199 tmp_launch_file.writelines(string)
200 tmp_launch_file.close()
202 return tmp_launch_file.name
206 Retrieve joint limits in radians for joint in self.joint_name 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)]
234 launch a dynamically created launch file 238 launch_string =
"roslaunch " + filename
240 self.subprocess_.append(subprocess.Popen(launch_string.split()))
246 a rosgui plugin for tuning the sr_mechanism_controllers 250 Plugin.__init__(self, context)
251 self.setObjectName(
'SrGuiControllerTuner')
260 ui_file = os.path.join(rospkg.RosPack().get_path(
261 'sr_gui_controller_tuner'),
'uis',
'SrGuiControllerTuner.ui')
263 self._widget.setObjectName(
'SrControllerTunerUi')
264 context.add_widget(self.
_widget)
268 hand_parameters = self._hand_finder.get_hand_parameters()
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")
275 self.
_widget,
"warning",
"No hand is detected")
277 self._widget.select_prefix.setCurrentIndex(0)
278 self.
_prefix = hand_parameters.mapping.values()[0]
280 self._widget.select_prefix.currentIndexChanged[
296 rospkg.RosPack().get_path(
'sr_gui_controller_tuner'),
297 'data',
'controller_settings.xml'))
299 self.sr_controller_tuner_app_.prefix = self.
_prefix 300 self.sr_controller_tuner_app_.selected_prefix = self.
_prefix 302 self.sr_controller_tuner_app_.check_prefix()
306 self._widget.btn_refresh_ctrl.pressed.connect(
308 self._widget.dropdown_ctrl.currentIndexChanged.connect(
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(
318 self._widget.btn_set_selected.pressed.connect(
320 self._widget.btn_set_all.pressed.connect(
324 self._widget.btn_stop_mvts.pressed.connect(
336 self.move_threads.append(move_thread)
340 When controller type is changed clear the chosen file path and refresh the tree with the controller settings 350 Clear the chosen file path and disable the save button until user selects another path 352 self._widget.txt_file_path.setText(
"")
354 self._widget.btn_load.setEnabled(
False)
358 self._widget.btn_save_all.setEnabled(
False)
359 self._widget.btn_save_selected.setEnabled(
False)
363 Perform controller tuning and save settings to user specified file 364 sr_config stack must be installed 368 path_to_config = os.path.join(
369 rospkg.RosPack().get_path(
'sr_ethercat_hand_config'))
372 "couldn't find the sr_ethercat_hand_config package, do you have the sr_config stack installed?")
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" 385 filter_files =
"*controllers.yaml" 387 if self.sr_controller_tuner_app_.control_mode ==
"PWM":
388 filter_files =
"*s_PWM.yaml" 390 filter_files =
"*s.yaml" 393 filter_files =
"Config (*motor" + filter_files +
")" 394 subpath =
"/controls/motors/" + config_subdir
396 filter_files =
"Config (*position_controller" + filter_files +
")" 398 filter_files =
"Config (*muscle_joint_position_controller" + \
401 filter_files =
"Config (*velocity_controller" + filter_files +
")" 403 filter_files =
"Config (*position_velocity" + filter_files +
")" 405 filter_files =
"Config (*effort_controller" + filter_files +
")" 407 path_to_config += subpath
409 filename, _ = QFileDialog.getOpenFileName(
410 self._widget.tree_ctrl_settings, self._widget.tr(
411 'Save Controller Settings'),
414 self._widget.tr(filter_files))
421 self._widget.txt_file_path.setText(filename)
423 self._widget.btn_load.setEnabled(
True)
427 self._widget.btn_save_all.setEnabled(
True)
428 self._widget.btn_save_selected.setEnabled(
True)
432 reload the parameters in rosparam, then refresh the tree widget 435 for params, namespace
in paramlist:
436 rosparam.upload_params(namespace, params)
443 Save only the selected controllers 445 selected_items = self._widget.tree_ctrl_settings.selectedItems()
447 if len(selected_items) == 0:
449 self._widget.tree_ctrl_settings,
"Warning",
"No motors selected.")
451 for it
in selected_items:
452 if str(it.text(1)) !=
"":
459 for motor
in self.ctrl_widgets.keys():
464 Sets the current values for selected controllers using the ros service. 466 selected_items = self._widget.tree_ctrl_settings.selectedItems()
468 if len(selected_items) == 0:
470 self._widget.tree_ctrl_settings,
"Warning",
"No motors selected.")
472 for it
in selected_items:
473 if str(it.text(1)) !=
"":
478 Sets the current values for all controllers using the ros service. 480 for motor
in self.ctrl_widgets.keys():
485 Calls refresh_controller_tree_ after preparing widgets 487 ctrls = self.sr_controller_tuner_app_.get_ctrls()
488 self.sr_controller_tuner_app_.refresh_control_mode()
490 self._widget.dropdown_ctrl.clear()
492 self._widget.dropdown_ctrl.addItem(ctrl)
493 self.controllers_in_dropdown.append(ctrl)
499 Sets the prefix in the controller tuner app and 500 Refreshes the controllers 503 self.sr_controller_tuner_app_.selected_prefix = self.
_prefix +
"/" 504 self.sr_controller_tuner_app_.check_prefix()
509 retrieve settings for joint with given name 514 for item
in dict_of_widgets.items():
516 settings[item[0]] = item[1].value()
517 except AttributeError:
519 settings[item[0]] = 1
if item[
520 1].checkState() == Qt.Checked
else 0
521 except AttributeError:
527 Sets the current values for the given controller using the ros service. 532 success = self.sr_controller_tuner_app_.set_controller(
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.")
540 QMessageBox.warning(self._widget.tree_ctrl_settings,
"Warning",
541 "Failed to set the PID values for joint " + joint_name +
".")
545 Saves the current values for the given controller using the ros service. 550 self.sr_controller_tuner_app_.save_controller(
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. 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)
567 self._widget.btn_set_selected.setEnabled(
True)
568 self._widget.btn_set_all.setEnabled(
True)
569 self._widget.btn_stop_mvts.setEnabled(
True)
572 ctrl_settings = self.sr_controller_tuner_app_.get_controller_settings(
575 self._widget.tree_ctrl_settings.clear()
576 self._widget.tree_ctrl_settings.setColumnCount(
577 ctrl_settings.nb_columns)
582 for header
in ctrl_settings.headers:
583 tmp_headers.append(header[
"name"])
584 self._widget.tree_ctrl_settings.setHeaderLabels(tmp_headers)
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]
594 motor_item = QTreeWidgetItem(finger_item, motor_settings)
595 self._widget.tree_ctrl_settings.addTopLevelItem(motor_item)
597 parameter_values = self.sr_controller_tuner_app_.load_parameters(
598 controller_type, motor_name)
600 if parameter_values != -1:
605 if not self.sr_controller_tuner_app_.edit_only_mode:
608 frame_buttons = QFrame()
609 layout_buttons = QHBoxLayout()
610 btn_plot = QPushButton(
"Plot")
616 layout_buttons.addWidget(btn_plot)
618 if self.
controller_type in [
"Position",
"Muscle Position",
"Mixed Position/Velocity"]:
620 btn_move = QPushButton(
"Move")
622 "btn_move"] = btn_move
627 layout_buttons.addWidget(btn_move)
628 frame_buttons.setLayout(layout_buttons)
630 self._widget.tree_ctrl_settings.setItemWidget(
631 motor_item, 0, frame_buttons)
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))
639 if item[
"type"] ==
"Bool":
640 check_box = QCheckBox()
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).")
648 self._widget.tree_ctrl_settings.setItemWidget(
649 motor_item, index_item, check_box)
652 param_name] = check_box
654 if item[
"type"] ==
"Int":
655 spin_box = QSpinBox()
657 int(item[
"min"]), int(item[
"max"]))
659 int(parameter_values[param_name]))
661 param_name] = spin_box
663 self._widget.tree_ctrl_settings.setItemWidget(
664 motor_item, index_item, spin_box)
666 if item[
"type"] ==
"Float":
667 spin_box = QDoubleSpinBox()
668 spin_box.setRange(-65535.0, 65535.0)
669 spin_box.setDecimals(3)
672 float(parameter_values[param_name]))
674 param_name] = spin_box
676 self._widget.tree_ctrl_settings.setItemWidget(
677 motor_item, index_item, spin_box)
679 motor_item.setExpanded(
True)
682 1,
"parameters not found - controller tuning disabled")
683 finger_item.setExpanded(
True)
684 hand_item.setExpanded(
True)
686 for col
in range(0, self._widget.tree_ctrl_settings.columnCount()):
687 self._widget.tree_ctrl_settings.resizeColumnToContents(col)
691 move_thread.__del__()
699 self._publisher.unregister()
def restore_settings(self, global_settings, perspective_settings)
def set_controller(self, joint_name)
def __init__(self, context)
def on_changed_controller_type_(self, index=None)
joint_index_in_joint_state_
def on_btn_move_pressed_(self, joint_name, btn)
def on_btn_plot_pressed_(self, joint_name, btn)
def save_controller(self, joint_name)
def create_launch_file_(self)
def on_btn_refresh_ctrl_clicked_(self)
def js_callback_(self, msg)
def read_settings(self, joint_name)
def prefix_selected(self, prefix)
def on_btn_set_selected_clicked_(self)
def on_btn_save_all_clicked_(self)
def on_btn_save_selected_clicked_(self)
def __init__(self, parent=None, joint_name="FFJ0", controller_type="Motor Force")
def reset_file_path(self)
def _unregisterPublisher(self)
def refresh_controller_tree_(self, controller_type="Motor Force")
def on_btn_load_clicked_(self)
def save_settings(self, global_settings, perspective_settings)
def on_btn_select_file_path_clicked_(self)
def shutdown_plugin(self)
def on_btn_set_all_clicked_(self)
def on_btn_stop_mvts_clicked_(self)
def __init__(self, parent=None, joint_name="FFJ0", controller_type="Motor Force")