00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 import os
00033 import rospy
00034 import rospkg
00035
00036 from time import sleep
00037
00038 from qt_gui.plugin import Plugin
00039 from python_qt_binding import loadUi
00040
00041 from QtGui import QMessageBox, QWidget, QIcon
00042 from controller_manager_msgs.srv import ListControllers
00043 from controller_manager_msgs.srv import SwitchController, LoadController
00044 from sr_robot_msgs.srv import ChangeControlType
00045 from sr_robot_msgs.msg import ControlType
00046 from sr_utilities.hand_finder import HandFinder
00047
00048
00049 class SrGuiAdvancedControls(Plugin):
00050
00051 """
00052 A rosgui plugin for loading the different controllers
00053 """
00054 ICON_DIR = os.path.join(
00055 rospkg.RosPack().get_path('sr_visualization_icons'), 'icons')
00056 CONTROLLER_ON_ICON = QIcon(os.path.join(ICON_DIR, 'green.png'))
00057 CONTROLLER_OFF_ICON = QIcon(os.path.join(ICON_DIR, 'red.png'))
00058
00059 def populate_controllers(self):
00060
00061 self.hand_ids = []
00062 hand_joint_prefixes = []
00063
00064 if rospy.has_param("/hand/mapping"):
00065 hand_mapping = rospy.get_param("/hand/mapping")
00066 for _, value in hand_mapping.items():
00067
00068
00069 if self._prefix in value:
00070 self.hand_ids.append(value)
00071 else:
00072 self.hand_ids.append("")
00073
00074 if rospy.has_param("/hand/joint_prefix"):
00075 hand_joint_prefix_mapping = rospy.get_param("/hand/joint_prefix")
00076 for _, value in hand_joint_prefix_mapping.items():
00077
00078
00079 if self._prefix in value:
00080 hand_joint_prefixes.append(value)
00081 if len(hand_joint_prefixes) == 0:
00082 QMessageBox.warning(self._widget, "Warning",
00083 "No hand found with prefix :" + self._prefix)
00084 hand_joint_prefixes.append("")
00085 else:
00086 rospy.loginfo("no joint prefix found, not appending prefix")
00087 hand_joint_prefixes.append("")
00088
00089 joints = ["ffj0", "ffj3", "ffj4",
00090 "mfj0", "mfj3", "mfj4",
00091 "rfj0", "rfj3", "rfj4",
00092 "lfj0", "lfj3", "lfj4", "lfj5",
00093 "thj1", "thj2", "thj3", "thj4", "thj5",
00094 "wrj1", "wrj2"]
00095 self.controllers = {
00096 "effort": [
00097 "sh_{0}{1}_effort_controller".format(hand_joint_prefix, joint)
00098 for joint in joints for hand_joint_prefix in
00099 hand_joint_prefixes],
00100 "position": [
00101 "sh_{0}{1}_position_controller".format(hand_joint_prefix,
00102 joint)
00103 for joint in joints for hand_joint_prefix in
00104 hand_joint_prefixes],
00105 "mixed": [
00106 "sh_{0}{1}_mixed_position_velocity_controller".format(
00107 hand_joint_prefix, joint)
00108 for joint in joints for hand_joint_prefix in
00109 hand_joint_prefixes],
00110 "velocity": [
00111 "sh_{0}{1}_velocity_controller".format(
00112 hand_joint_prefix, joint)
00113 for joint in joints for hand_joint_prefix in
00114 hand_joint_prefixes], "stop": []}
00115
00116 self.managed_controllers = [
00117 cont for type_conts in self.controllers.itervalues()
00118 for cont in type_conts]
00119
00120 def __init__(self, context):
00121 super(SrGuiAdvancedControls, self).__init__(context)
00122 self.setObjectName('SrGuiAdvancedControls')
00123
00124 self._publisher = None
00125
00126 self._widget = QWidget()
00127
00128 ui_file = os.path.join(
00129 rospkg.RosPack().get_path('sr_gui_advanced_controls'), 'uis',
00130 'SrAdvancedControls.ui')
00131 loadUi(ui_file, self._widget)
00132 self._widget.setObjectName('SrAdvancedControlsUI')
00133 context.add_widget(self._widget)
00134
00135
00136 self._hand_finder = HandFinder()
00137 hand_parameters = self._hand_finder.get_hand_parameters()
00138
00139 self._prefix = ""
00140 for hand in hand_parameters.mapping:
00141 self._widget.select_prefix.addItem(hand_parameters.mapping[hand])
00142
00143 if not hand_parameters.mapping:
00144 rospy.logerr("No hand detected")
00145 QMessageBox.warning(
00146 self._widget, "warning", "No hand is detected")
00147 else:
00148 self._widget.select_prefix.setCurrentIndex(0)
00149 self._prefix = hand_parameters.mapping.values()[0]
00150
00151 self._widget.select_prefix.currentIndexChanged['QString'].connect(
00152 self.prefix_selected)
00153
00154 self.populate_controllers()
00155
00156
00157 self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
00158 self._widget.btn_mixed.setChecked(False)
00159 self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
00160 self._widget.btn_effort.setChecked(False)
00161 self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00162 self._widget.btn_position.setChecked(False)
00163 self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
00164 self._widget.btn_velocity.setChecked(False)
00165
00166
00167 self._widget.btn_stop.pressed.connect(self.on_stop_ctrl_clicked_)
00168 self._widget.btn_effort.pressed.connect(self.on_effort_ctrl_clicked_)
00169 self._widget.btn_position.pressed.connect(
00170 self.on_position_ctrl_clicked_)
00171 self._widget.btn_mixed.pressed.connect(self.on_mixed_ctrl_clicked_)
00172 self._widget.btn_velocity.pressed.connect(
00173 self.on_velocity_ctrl_clicked_)
00174
00175
00176 if os.environ.get('PWM_CONTROL') in [None, '0']:
00177 self._widget.radioButtonTorque.setChecked(True)
00178 self._widget.radioButtonPWM.setChecked(False)
00179 else:
00180 self._widget.radioButtonTorque.setChecked(False)
00181 self._widget.radioButtonPWM.setChecked(True)
00182
00183 self._widget.radioButtonTorque.toggled.connect(
00184 self.on_control_mode_radio_button_toggled_)
00185 self._widget.radioButtonPWM.toggled.connect(
00186 self.on_control_mode_radio_button_toggled_)
00187
00188 def on_control_mode_radio_button_toggled_(self, checked):
00189 """
00190 Switch between FORCE, PWM modes
00191 We only react to the currently ON radio button event
00192 """
00193 if checked:
00194 change_type_msg = ChangeControlType()
00195 if self._widget.radioButtonTorque.isChecked():
00196 change_type_msg.control_type = ControlType.FORCE
00197 rospy.loginfo("Change Control mode to FORCE")
00198 else:
00199 change_type_msg.control_type = ControlType.PWM
00200 rospy.loginfo("Change Control mode to PWM")
00201 self.change_force_ctrl_type(change_type_msg)
00202
00203 def on_stop_ctrl_clicked_(self):
00204 """
00205 Stop controller
00206 """
00207 self._widget.btn_stop.setEnabled(False)
00208 self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
00209 self._widget.btn_mixed.setChecked(False)
00210 self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
00211 self._widget.btn_effort.setChecked(False)
00212 self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00213 self._widget.btn_position.setChecked(False)
00214 self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
00215 self._widget.btn_velocity.setChecked(False)
00216 self.change_ctrl("stop")
00217 self._widget.btn_stop.setEnabled(True)
00218
00219 def on_effort_ctrl_clicked_(self):
00220 """
00221 Effort controller selected
00222 """
00223 self._widget.btn_effort.setEnabled(False)
00224 if not self._widget.btn_effort.isChecked():
00225 self._widget.btn_effort.setIcon(self.CONTROLLER_ON_ICON)
00226 self._widget.btn_effort.setChecked(True)
00227 self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00228 self._widget.btn_position.setChecked(False)
00229 self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
00230 self._widget.btn_mixed.setChecked(False)
00231 self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
00232 self._widget.btn_velocity.setChecked(False)
00233 rospy.loginfo("Effort checked: " + str(
00234 self._widget.btn_effort.isChecked()))
00235 self.change_ctrl("effort")
00236 else:
00237 self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
00238 self._widget.btn_effort.setChecked(False)
00239 rospy.loginfo("Effort checked: " + str(
00240 self._widget.btn_effort.isChecked()))
00241 self.change_ctrl("stop")
00242 self._widget.btn_effort.setEnabled(True)
00243
00244 def on_position_ctrl_clicked_(self):
00245 """
00246 Position controller selected
00247 """
00248 self._widget.btn_position.setEnabled(False)
00249 if not self._widget.btn_position.isChecked():
00250 self._widget.btn_position.setIcon(self.CONTROLLER_ON_ICON)
00251 self._widget.btn_position.setChecked(True)
00252 self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
00253 self._widget.btn_effort.setChecked(False)
00254 self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
00255 self._widget.btn_mixed.setChecked(False)
00256 self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
00257 self._widget.btn_velocity.setChecked(False)
00258 rospy.loginfo("Position checked: " +
00259 str(self._widget.btn_position.isChecked()))
00260 self.change_ctrl("position")
00261 else:
00262 self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00263 self._widget.btn_position.setChecked(False)
00264 rospy.loginfo("Position checked: " +
00265 str(self._widget.btn_position.isChecked()))
00266 self.change_ctrl("stop")
00267 self._widget.btn_position.setEnabled(True)
00268
00269 def on_mixed_ctrl_clicked_(self):
00270 """
00271 Mixed controller selected
00272 """
00273 self._widget.btn_mixed.setEnabled(False)
00274 if not self._widget.btn_mixed.isChecked():
00275 self._widget.btn_mixed.setIcon(self.CONTROLLER_ON_ICON)
00276 self._widget.btn_mixed.setChecked(True)
00277 self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
00278 self._widget.btn_effort.setChecked(False)
00279 self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00280 self._widget.btn_position.setChecked(False)
00281 self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
00282 self._widget.btn_velocity.setChecked(False)
00283 rospy.loginfo("Mixed checked: " +
00284 str(self._widget.btn_mixed.isChecked()))
00285 self.change_ctrl("mixed")
00286 else:
00287 self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
00288 self._widget.btn_mixed.setChecked(False)
00289 rospy.loginfo("Mixed checked: " +
00290 str(self._widget.btn_mixed.isChecked()))
00291 self.change_ctrl("stop")
00292 self._widget.btn_mixed.setEnabled(True)
00293
00294 def on_velocity_ctrl_clicked_(self):
00295 """
00296 Velocity controller selected
00297 """
00298 self._widget.btn_velocity.setEnabled(False)
00299 if not self._widget.btn_velocity.isChecked():
00300 self._widget.btn_velocity.setIcon(self.CONTROLLER_ON_ICON)
00301 self._widget.btn_velocity.setChecked(True)
00302 self._widget.btn_effort.setIcon(self.CONTROLLER_OFF_ICON)
00303 self._widget.btn_effort.setChecked(False)
00304 self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00305 self._widget.btn_position.setChecked(False)
00306 self._widget.btn_mixed.setIcon(self.CONTROLLER_OFF_ICON)
00307 self._widget.btn_mixed.setChecked(False)
00308 rospy.loginfo("Velocity checked: " +
00309 str(self._widget.btn_velocity.isChecked()))
00310 self.change_ctrl("velocity")
00311 else:
00312 self._widget.btn_velocity.setIcon(self.CONTROLLER_OFF_ICON)
00313 self._widget.btn_velocity.setChecked(False)
00314 rospy.loginfo("Velocity checked: " +
00315 str(self._widget.btn_velocity.isChecked()))
00316 self.change_ctrl("stop")
00317 self._widget.btn_velocity.setEnabled(True)
00318
00319 def change_ctrl(self, controller):
00320 """
00321 Switch the current controller
00322 """
00323 success = True
00324 list_controllers = rospy.ServiceProxy(
00325 'controller_manager/list_controllers', ListControllers)
00326 try:
00327 resp1 = list_controllers()
00328 except rospy.ServiceException:
00329 success = False
00330
00331 if success:
00332 controllers_to_stop = [
00333 c.name for c in resp1.controller
00334 if c.state == "running" and c.name in self.managed_controllers]
00335 all_loaded_controllers = [c.name for c in resp1.controller]
00336
00337 controllers_to_start = self.controllers[controller]
00338
00339 load_controllers = None
00340 for load_control in controllers_to_start:
00341 if load_control not in all_loaded_controllers:
00342 try:
00343 load_controllers = rospy.ServiceProxy(
00344 'controller_manager/load_controller',
00345 LoadController)
00346 resp1 = load_controllers(load_control)
00347 except rospy.ServiceException:
00348 success = False
00349 if not resp1.ok:
00350 success = False
00351
00352 switch_controllers = rospy.ServiceProxy(
00353 'controller_manager/switch_controller', SwitchController)
00354 try:
00355 resp1 = switch_controllers(
00356 controllers_to_start, controllers_to_stop,
00357 SwitchController._request_class.BEST_EFFORT)
00358 except rospy.ServiceException:
00359 success = False
00360
00361 if not resp1.ok:
00362 success = False
00363
00364 if not success:
00365 rospy.logwarn(
00366 "Failed to change some of the controllers. "
00367 "This is normal if this is not a 5 finger hand.")
00368
00369 def change_force_ctrl_type(self, chng_type_msg):
00370 """
00371 Calls the service (realtime_loop/change_control_type) that allows to
00372 tell the driver (sr_robot_lib)
00373 which type of force control has to be sent to the motor:
00374 - torque demand (sr_robot_msgs::ControlType::FORCE)
00375 - PWM (sr_robot_msgs::ControlType::PWM)
00376 it will deactivate the Effort, Position, Mixed and Velocity buttons
00377 for 3 secs to allow hardware controllers to be updated
00378 """
00379 success = True
00380 for hand_id in self.hand_ids:
00381 srv_path = 'realtime_loop/' + hand_id + '/change_control_type'
00382
00383 srv_path.replace("//", "/")
00384 change_control_type = rospy.ServiceProxy(srv_path,
00385 ChangeControlType)
00386 try:
00387 resp1 = change_control_type(chng_type_msg)
00388 if resp1.result.control_type != chng_type_msg.control_type:
00389 success = False
00390 except rospy.ServiceException:
00391 success = False
00392
00393
00394 self._widget.btn_effort.setEnabled(False)
00395 self._widget.btn_position.setEnabled(False)
00396 self._widget.btn_mixed.setEnabled(False)
00397 self._widget.btn_velocity.setEnabled(False)
00398 sleep(3)
00399 self._widget.btn_effort.setEnabled(True)
00400 self._widget.btn_position.setEnabled(True)
00401 self._widget.btn_mixed.setEnabled(True)
00402 self._widget.btn_velocity.setEnabled(True)
00403
00404 if not success:
00405 QMessageBox.warning(self._widget, "Warning",
00406 "Failed to change the control type.")
00407
00408 def prefix_selected(self, prefix):
00409 self._prefix = prefix
00410 self.populate_controllers()
00411
00412 def _unregisterPublisher(self):
00413 if self._publisher is not None:
00414 self._publisher.unregister()
00415 self._publisher = None
00416
00417 def shutdown_plugin(self):
00418 self._unregisterPublisher()
00419
00420 def save_settings(self, global_settings, perspective_settings):
00421 pass
00422
00423 def restore_settings(self, global_settings, perspective_settings):
00424 pass