42 roslib.load_manifest(
"hrpsys")
51 if not os.environ.has_key(
'ORBgiopMaxMsgSize'):
52 os.environ[
'ORBgiopMaxMsgSize'] =
'2147483648' 56 import OpenRTM_aist.RTM_IDL
58 from waitInput
import waitInputConfirm, waitInputSelect
60 from distutils.version
import StrictVersion
62 SWITCH_ON = OpenHRP.RobotHardwareService.SWITCH_ON
63 SWITCH_OFF = OpenHRP.RobotHardwareService.SWITCH_OFF
64 _MSG_ASK_ISSUEREPORT =
'Your report to ' + \
65 'https://github.com/start-jsk/rtmros_hironx/issues ' + \
66 'about the issue you are seeing is appreciated.' 67 _MSG_RESTART_QNX =
'You may want to restart QNX/ControllerBox afterward' 70 from sys
import modules
72 thismod = modules[modname]
74 raise ValueError(modname)
75 these_symbols = dir(thismod)
80 raise ValueError(
'must supply a finite list for paranoid')
82 these_symbols = paranoid[:]
84 for mod
in modules.values():
87 except AttributeError:
90 for symbol
in these_symbols:
91 if symbol[:2] ==
'__':
95 except AttributeError:
99 default_frame_name =
'WAIST' 103 A method only inteded for class-internal usage. 105 @since: 315.12.1 or higher 106 @type method: A Python function object. 107 @param method: One of the following Python function objects defined in class HrpsysConfigurator: 108 [getCurrentPose, getCurrentPosition, getCurrentReference, getCurrentRPY, 109 getReferencePose, getReferencePosition, getReferenceReference, getReferenceRPY] 110 @param frame_name str: set reference frame name (available from version 315.2.5) 111 @rtype: {str: [float]} 112 @return: Dictionary of the values for each kinematic group. 113 Example (using getCurrentPosition): 115 [{CHEST_JOINT0: [0.0, 0.0, 0.0]}, 116 {HEAD_JOINT1: [0.0, 0.0, 0.5694999999999999]}, 117 {RARM_JOINT5: [0.3255751238415409, -0.18236314012331808, 0.06762452267747099]}, 118 {LARM_JOINT5: [0.3255751238415409, 0.18236314012331808, 0.06762452267747099]}] 120 _geometry_methods = [
'getCurrentPose',
'getCurrentPosition',
121 'getCurrentReference',
'getCurrentRPY',
122 'getReferencePose',
'getReferencePosition',
123 'getReferenceReference',
'getReferenceRPY']
124 if method.__name__
not in _geometry_methods:
125 raise NameError(
"Passed method {} is not supported.".format(method))
126 for kinematic_group
in self.Groups:
129 eef_name = kinematic_group[1][-1]
131 result = method(eef_name, frame_name)
132 except RuntimeError
as e:
134 print(
"{}: {}".format(eef_name, method(eef_name)))
135 raise RuntimeError(
"Since no link name passed, ran it for all" 140 Returns the current physical pose of the specified joint. 141 cf. getReferencePose that returns commanded value. 145 IN: robot.getCurrentPose('LARM_JOINT5') 146 OUT: [-0.0017702356144599085, 147 0.00019034630541264752, 150 0.00012155879975329215, 152 0.0001901314142046251, 155 -0.00012122202968358842, 156 -0.001770258707652326, 165 @param lname: Name of the link. 166 @param frame_name str: set reference frame name (from 315.2.5) 167 @rtype: list of float 168 @return: Rotational matrix and the position of the given joint in 169 1-dimensional list, that is: 178 self._get_geometry(self.getReferenceRPY, frame_name)
187 if StrictVersion(self.fk_version) >= StrictVersion(
'315.2.5'):
188 if self.default_frame_name
and frame_name
is None:
189 frame_name = self.default_frame_name
190 if frame_name
and not ':' in lname:
191 lname = lname +
':' + frame_name
194 print(
'frame_name ('+lname+
') is not supported')
195 pose = self.fk_svc.getCurrentPose(lname)
197 raise RuntimeError(
"Could not find reference : " + lname)
202 Returns the current commanded pose of the specified joint. 203 cf. getCurrentPose that returns physical pose. 206 @param lname: Name of the link. 207 @param frame_name str: set reference frame name (from 315.2.5) 208 @rtype: list of float 209 @return: Rotational matrix and the position of the given joint in 210 1-dimensional list, that is: 220 self._get_geometry(self.getReferenceRPY, frame_name)
221 if StrictVersion(self.fk_version) >= StrictVersion(
'315.2.5'):
222 if self.default_frame_name
and frame_name
is None:
223 frame_name = self.default_frame_name
224 if frame_name
and not ':' in lname:
225 lname = lname +
':' + frame_name
228 print(
'frame_name ('+lname+
') is not supported')
229 pose = self.fk_svc.getReferencePose(lname)
231 raise RuntimeError(
"Could not find reference : " + lname)
236 Move the end-effector to the given absolute pose. 237 All d* arguments are in meter. 239 @param gname str: Name of the joint group. Case-insensitive 240 @param pos list of float: In meter. 241 @param rpy list of float: In radian. 242 @param tm float: Second to complete the command. 243 @param frame_name str: Name of the frame that this particular command 245 @return bool: False if unreachable. 247 print(gname, frame_name, pos, rpy, tm)
252 if gname.upper()
not in map (
lambda x : x[0].upper(), self.Groups):
253 print(
"setTargetPose failed. {} is not available in the kinematic groups. " 254 "Check available Groups (by e.g. self.Groups/robot.Groups). ".format(gname))
256 if StrictVersion(self.seq_version) >= StrictVersion(
'315.2.5'):
257 if self.default_frame_name
and frame_name
is None:
258 frame_name = self.default_frame_name
259 if frame_name
and not ':' in gname:
260 gname = gname +
':' + frame_name
262 if frame_name
and not ':' in gname:
263 print(
'frame_name ('+gname+
') is not supported')
264 result = self.seq_svc.setTargetPose(gname, pos, rpy, tm)
266 print(
"setTargetPose failed. Maybe SequencePlayer failed to solve IK.\n" 267 +
"Currently, returning IK result error\n" 268 +
"(like the one in https://github.com/start-jsk/rtmros_hironx/issues/103)" 269 +
" is not implemented. Patch is welcomed.")
274 @see: <a href = "https://github.com/fkanehiro/hrpsys-base/blob/master/" + 275 "python/hrpsys_config.py">HrpsysConfigurator</a> 277 This class holds methods that are specific to Kawada Industries' dual-arm 280 For the API doc for the derived methods, please see the parent 281 class via the link above; nicely formatted api doc web page 282 isn't available yet (discussed in 283 https://github.com/fkanehiro/hrpsys-base/issues/268). 286 Groups = [[
'torso', [
'CHEST_JOINT0']],
287 [
'head', [
'HEAD_JOINT0',
'HEAD_JOINT1']],
288 [
'rarm', [
'RARM_JOINT0',
'RARM_JOINT1',
'RARM_JOINT2',
289 'RARM_JOINT3',
'RARM_JOINT4',
'RARM_JOINT5']],
290 [
'larm', [
'LARM_JOINT0',
'LARM_JOINT1',
'LARM_JOINT2',
291 'LARM_JOINT3',
'LARM_JOINT4',
'LARM_JOINT5']]]
294 For OffPose and _InitialPose, the angles of each joint are listed in the 295 ordered as defined in Groups variable.''' 298 [25, -139, -157, 45, 0, 0],
299 [-25, -139, -157, -45, 0, 0],
303 _InitialPose = [[0], [0, 0],
304 [-0.6, 0, -100, 15.2, 9.4, 3.2],
305 [0.6, 0, -100, -15.2, 9.4, -3.2],
311 _InitialPose_Factory = [[0], [0, 0],
312 [-0, 0, -130, 0, 0, 0],
313 [0, 0, -130, 0, 0, 0],
316 INITPOS_TYPE_EVEN = 0
317 INITPOS_TYPE_FACTORY = 1
319 HandGroups = {
'rhand': [2, 3, 4, 5],
'lhand': [6, 7, 8, 9]}
327 hrpsys_version =
'0.0.0' 329 _MSG_IMPEDANCE_CALL_DONE = (
" call is done. This does't necessarily mean " +
330 "the function call was successful, since not " +
331 "all methods internally called return status")
333 def init(self, robotname="HiroNX(Robot)0
", url=""): 335 Calls init from its superclass, which tries to connect RTCManager, 336 looks for ModelLoader, and starts necessary RTC components. Also runs 338 Also internally calls setSelfGroups(). 344 print(self.configurator_name +
"waiting ModelLoader")
345 HrpsysConfigurator.waitForModelLoader(self)
346 print(self.configurator_name +
"start hrpsys")
348 print(self.configurator_name +
"finding RTCManager and RobotHardware")
349 HrpsysConfigurator.waitForRTCManagerAndRoboHardware(self, robotname=robotname)
350 print self.configurator_name,
"Hrpsys controller version info: " 352 print self.configurator_name,
" ms = ", self.ms
353 if self.ms
and self.ms.ref :
354 print self.configurator_name,
" ref = ", self.ms.ref
355 if self.ms
and self.ms.ref
and len(self.ms.ref.get_component_profiles()) > 0:
356 print self.configurator_name,
" version = ", self.ms.ref.get_component_profiles()[0].version
357 if self.ms
and self.ms.ref
and len(self.ms.ref.get_component_profiles()) > 0
and StrictVersion(self.ms.ref.get_component_profiles()[0].version) < StrictVersion(
'315.2.0'):
358 sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)),
'hrpsys_315_1_9/hrpsys'))
360 import AbsoluteForceSensorService_idl
361 import ImpedanceControllerService_idl
367 if set([rn[0]
for rn
in self.
getRTCList()]).issubset(set([x.name()
for x
in self.ms.get_components()])) :
368 print(self.configurator_name +
"hrpsys components are already created and running")
369 self.findComps(max_timeout_count=0, verbose=
True)
371 print(self.configurator_name +
"no hrpsys components found running. creating now")
374 print(self.configurator_name +
"connecting hrpsys components")
377 print(self.configurator_name +
"activating hrpsys components")
380 print(self.configurator_name +
"setup hrpsys logger")
383 print(self.configurator_name +
"setup joint groups for hrpsys controller")
386 print(self.configurator_name +
'\033[32minitialized successfully\033[0m')
392 print(self.configurator_name +
'\033[34mCould not get hrpsys_version\033[0m')
400 Move arms to the predefined (as member variable) pose where robot can 401 be safely turned off. 404 @param tm: Second to complete. 406 for i
in range(len(self.
Groups)):
407 self.setJointAnglesOfGroup(self.
Groups[i][0], self.
OffPose[i], tm,
409 for i
in range(len(self.
Groups)):
410 self.seq_svc.waitInterpolationOfGroup(self.
Groups[i][0])
415 Move arms to the predefined (as member variable) "initialized" pose. 418 @param tm: Second to complete. 420 @param wait: If true, other command to the robot's joints wait until 421 this command returns (done by running 422 SequencePlayer.waitInterpolationOfGroup). 423 @type init_pose_type: int 424 @param init_pose_type: 0: default init pose (specified as _InitialPose) 425 1: factory init pose (specified as 426 _InitialPose_Factory) 434 for i
in range(len(self.
Groups)):
437 '{}, JntAnglesOfGr={}, INITPOSE[i]={}, tm={}, wait={}'.format(
438 self.configurator_name, self.
Groups[i][0], _INITPOSE[i],
440 ret &= self.setJointAnglesOfGroup(self.
Groups[i][0],
444 for i
in range(len(self.
Groups)):
445 self.seq_svc.waitInterpolationOfGroup(self.
Groups[i][0])
450 @see: HrpsysConfigurator.getRTCList 453 @rerutrn List of available components. Each element consists of a list 454 of abbreviated and full names of the component. 457 [
'seq',
"SequencePlayer"],
458 [
'sh',
"StateHolder"],
459 [
'fk',
"ForwardKinematics"],
460 [
'ic',
"ImpedanceController"],
461 [
'el',
"SoftErrorLimiter"],
462 [
'co',
"CollisionDetector"],
463 [
'sc',
"ServoController"],
464 [
'log',
"DataLogger"],
470 if self.ms
and self.ms.ref
and len(self.ms.ref.get_component_profiles()) > 0:
471 for rtc
in copy.deepcopy(rtclist):
473 enable = next(p
for p
474 in self.ms.ref.get_component_profiles()[0].properties
475 if p.name == (rtc[1] +
'.enable')).value.value()
476 except StopIteration:
480 elif enable !=
'YES':
481 print(self.configurator_name +
482 '\033[31mConfig "' + (rtc[1] +
'.enable') +
'" is ' +
483 enable +
'. Set YES or NO\033[0m')
487 co_rtc = [
'co',
"CollisionDetector"]
488 if co_rtc
not in rtclist:
490 elif self.ms
and self.ms.ref
and len(self.ms.ref.get_component_profiles()) > 0:
493 in self.ms.ref.get_component_profiles()[0].properties
494 if p.name == (co_rtc[1] +
'.enable')).value.value()
495 except StopIteration:
496 rtclist.remove(co_rtc)
498 rtclist.remove(co_rtc)
500 if hasattr(self,
'rmfo'):
501 self.ms.load(
"RemoveForceSensorLinkOffset")
502 self.ms.load(
"AbsoluteForceSensor")
503 if "RemoveForceSensorLinkOffset" in self.ms.get_factory_names():
504 rtclist.append([
'rmfo',
"RemoveForceSensorLinkOffset"])
505 elif "AbsoluteForceSensor" in self.ms.get_factory_names():
506 rtclist.append([
'rmfo',
"AbsoluteForceSensor"])
508 print "Component rmfo is not loadable." 520 Set the stretch between two fingers of the specified hand as 521 hardcoded value (100mm), by internally calling self.setHandWidth. 524 @param hand: Name of the hand joint group. In the default 525 setting of HIRONX, hand joint groups are defined 526 in member 'HandGroups' where 'lhand' and 'rhand' 534 Close 2-finger hand, by internally calling self.setHandWidth 538 @param hand: Name of the hand joint group. In the default 539 setting of HIRONX, hand joint groups are defined 540 in member 'HandGroups' where 'lhand' and 'rhand' 549 @param hand: Name of the hand joint group. In the default 550 setting of HIRONX, hand joint groups are defined 551 in member 'HandGroups' where 'lhand' and 'rhand' 553 @type angles: OpenHRP::ServoControllerService::dSequence. 554 @param angles: List of (TODO: document). Elements are in degree. 555 @param tm: Time to complete the task. 557 self.sc_svc.setJointAnglesOfGroup(hand, angles, tm)
561 Set maximum torque for all existing hand components. 565 for i
in [v
for vs
in self.HandGroups.values()
for v
in vs]:
566 self.sc_svc.setMaxTorque(i, effort)
571 @param hand: Name of the hand joint group. In the default 572 setting of HIRONX, hand joint groups are defined 573 in member 'HandGroups' where 'lhand' and 'rhand' 575 @param width: Max=100. 576 @param tm: Time to complete the move. 578 @param effort: Passed to self.setHandEffort if set. Not set by default. 585 for h
in self.HandGroups.keys():
590 Negate the angle value for {2, 3, 6, 7}th element in av. 593 @param hand: Specifies hand. (TODO: List the possible values. Should be 594 listed in setHandJointAngles so just copy from its doc.) 596 @param av: angle of each joint of the specified arm 597 (TODO: need verified. Also what's the length of the list?) 598 @param tm: Time in second to complete the work. 600 for i
in [2, 3, 6, 7]:
606 TODO: Needs documented what this method does. 609 @return: None if the given width is invalid. 614 if width < 0.0
or width > (l1 + l2 - safetyMargin) * 2:
617 xPos = width / 2.0 + safetyMargin
619 a1radH = math.acos(a2Pos / l1)
620 a1rad = math.pi / 2.0 - a1radH
622 return a1rad, -a1rad, -a1rad, a1rad
626 Set to the hrpsys.SequencePlayer the groups of links and joints that 627 are statically defined as member variables (Groups) within this class. 629 That said, override Groups variable if you prefer link and joint 630 groups set differently. 635 self.seq_svc.addJointGroup(item[0], item[1])
636 for k, v
in self.HandGroups.iteritems():
638 self.sc_svc.addJointGroup(k, v)
642 Check whether joints have been calibrated. 645 if self.simulation_mode:
648 rstt = self.rh_svc.getStatus()
649 for item
in rstt.servoState:
656 Check whether servo control has been turned on. Check is done by 657 HIRONX.getActualState().servoState. 659 @param jname: Name of a link (that can be obtained by "hiro.Groups" 663 - any: This command will check all servos available. 664 - all: Same as 'any'. 666 @return: If jname is specified either 'any' or 'all', return False 667 if the control of any of servos isn't available. 669 if self.simulation_mode:
672 s_s = self.getActualState().servoState
673 if jname.lower() ==
'any' or jname.lower() ==
'all':
679 jid = eval(
'self.' + jname)
680 print self.configurator_name, s_s[jid]
681 if s_s[jid][0] & 1 == 0:
688 @type flatList: [int] 689 @param flatList: single dimension list, with its length depends on 690 'Groups' variable defined within this class. Excessive 691 elements will be dropped (see example below in @return) 693 eg. If the number of joints of the robot is 15, 694 len(flatList) should be 15. 696 @return: 2-dimensional list that has the same format with 700 ipython> flatlist = [0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 701 100, 110, 120, 130, 140, 150] 702 ipython> robot.flat2Groups(flatlist) 704 [30, 40, 50, 60, 70, 80], 705 [90, 100, 110, 120, 130, 140]] 711 joint_num = len(group[1])
712 retList.append(flatList[index: index + joint_num])
716 def servoOn(self, jname='all', destroy=1, tm=3):
718 Turn on servo motors at joint specified. 719 Joints need to be calibrated (otherwise error returns). 722 When this method does not seem to function as expected, try the 723 following first before you report to the developer's community: 725 - Manually move the arms to the safe pose where arms do not obstruct 726 to anything and they can move back to the initial pose by goInitial. 727 Then run the command again. 728 - Make sure the emergency switch is toggled back. 729 - Try running goActual() then servoOn(). 731 If none of the above did not solve your issue, please report with: 732 - The result of this command (%ROSDISTRO% is "indigo" as of May 2017): 734 Ubuntu$ rosversion hironx_ros_bridge 735 Ubuntu$ dpkg -p ros-%ROSDISTRO%-hironx-ros-bridge 738 @param jname: The value 'all' works iteratively for all servos. 739 @param destroy: Not used. 741 @param tm: Second to complete. 743 @return: 1 or -1 indicating success or failure, respectively. 747 waitInputConfirm(
'!! Calibrate Encoders with checkEncoders first !!\n\n')
762 '!! Robot Motion Warning (SERVO_ON) !!\n\n' 763 'Confirm RELAY switched ON\n' 764 'Push [OK] to switch servo ON(%s).' % (jname))
766 self.rh_svc.power(
'all', SWITCH_OFF)
773 self.seq_svc.removeJointGroup(
"larm")
774 self.seq_svc.removeJointGroup(
"rarm")
775 self.seq_svc.removeJointGroup(
"head")
776 self.seq_svc.removeJointGroup(
"torso")
778 print(self.configurator_name,
779 'Exception during servoOn while removing JoingGroup. ' +
780 _MSG_ASK_ISSUEREPORT)
785 print(self.configurator_name,
786 'Exception during servoOn while removing setSelfGroups. ' +
787 _MSG_ASK_ISSUEREPORT)
792 self.rh_svc.servo(jname, SWITCH_ON)
796 print self.configurator_name,
'servo on failed.' 799 print self.configurator_name,
'exception occured' 803 self.getActualState().angle))
804 print 'Move to Actual State, Just a minute.' 805 for i
in range(len(self.
Groups)):
806 self.setJointAnglesOfGroup(self.
Groups[i][0], angles[i], tm,
808 for i
in range(len(self.
Groups)):
809 self.seq_svc.waitInterpolationOfGroup(self.
Groups[i][0])
811 print self.configurator_name,
'post servo on motion trouble' 814 print 'Turn on Hand Servo' 816 is_servoon = self.sc_svc.servoOn()
817 print(
'Hands Servo on: ' + str(is_servoon))
819 print(
'One or more hand servos failed to turn on. Make sure all hand modules are properly cabled (' 820 + _MSG_RESTART_QNX +
') and run the command again.')
823 print(
'hrpsys ServoController not found. Ignore this if you' +
824 ' do not intend to use hand servo (e.g. NEXTAGE Open).' +
825 ' If you do intend, then' + _MSG_RESTART_QNX +
826 ' and run the command again.')
833 @param jname: The value 'all' works iteratively for all servos. 836 @return: 1 = all arm servo off. 2 = all servo on arms and hands off. 837 -1 = Something wrong happened. 840 if self.simulation_mode:
841 print self.configurator_name,
'omit servo off' 844 print 'Turn off Hand Servo' 846 self.sc_svc.servoOff()
849 if jname.lower() ==
'all':
850 self.rh_svc.power(
'all', SWITCH_OFF)
859 '!! Robot Motion Warning (Servo OFF)!!\n\n' 860 'Push [OK] to servo OFF (%s).' % (jname))
863 self.rh_svc.servo(
'all', SWITCH_OFF)
866 self.rh_svc.power(
'all', SWITCH_OFF)
869 print 'Turn off Hand Servo' 871 self.sc_svc.servoOff()
875 print self.configurator_name,
'servo off: communication error' 880 Run the encoder checking sequence for specified joints, 881 run goActual to adjust the direction values, and then turn servos on. 884 @param jname: The value 'all' works iteratively for all servos. 886 @param option: Possible values are follows (w/o double quote):\ 887 "-overwrite": Overwrite calibration value. 890 waitInputConfirm(
'Servo must be off for calibration')
894 waitInputConfirm(
'System has been calibrated')
897 self.rh_svc.power(
'all', SWITCH_ON)
898 msg =
'!! Robot Motion Warning !!\n'\
901 if option ==
'-overwrite':
902 msg = msg +
'calibrate(OVERWRITE MODE) ' 907 msg = msg +
'the Encoders of all.' 909 msg = msg +
'the Encoder of the Joint "' + jname +
'".' 912 waitInputConfirm(msg)
914 print "If you're connecting to the robot from remote, " + \
915 "make sure tunnel X (eg. -X option with ssh)." 916 self.rh_svc.power(
'all', SWITCH_OFF)
920 print self.configurator_name,
'calib-joint ' + jname +
' ' + option
921 self.rh_svc.initializeJointAngle(jname, option)
922 print self.configurator_name,
'done' 923 is_result_hw = is_result_hw
and self.rh_svc.power(
'all', SWITCH_OFF)
926 is_result_hw = is_result_hw
and self.rh_svc.servo(jname, SWITCH_ON)
929 print(
"Turning servos ({}) failed. This is likely because of issues happening in lower level. Please check if the Kawada's proprietary tool NextageOpenSupervisor returns without issue or not. If the issue persists, contact the manufacturer.".format(jname))
931 print 'Turn on Hand Servo' 933 self.sc_svc.servoOn()
942 ref_force = [0, 0, 0],
943 force_gain = [1, 1, 1],
944 ref_moment = [0, 0, 0],
945 moment_gain = [0, 0, 0],
948 reference_gain = 0.0,
949 manipulability_limit = 0.1):
951 @type arm: str name of artm to be controlled, this must be initialized 952 using setSelfGroups() 953 @param ref_{force, moment}: Target values at the target position. 954 Units: N, Nm, respectively. 955 @param {force, moment}_gain: multipliers to the eef offset position 956 vel_p and orientation vel_r. 3-dimensional 957 vector (then converted internally into a 960 ic_sensor_name =
'rhsensor' 961 ic_target_name =
'RARM_JOINT5' 963 ic_sensor_name =
'rhsensor' 964 ic_target_name =
'RARM_JOINT5' 966 ic_sensor_name =
'lhsensor' 967 ic_target_name =
'LARM_JOINT5' 969 print 'startImpedance: argument must be rarm or larm.' 972 self.ic_svc.setImpedanceControllerParam(
973 OpenHRP.ImpedanceControllerService.impedanceParam(
974 name = ic_sensor_name,
975 base_name =
'CHEST_JOINT0',
976 target_name = ic_target_name,
983 ref_force = ref_force,
984 force_gain = force_gain,
985 ref_moment = ref_moment,
986 moment_gain = moment_gain,
988 avoid_gain = avoid_gain,
989 reference_gain = reference_gain,
990 manipulability_limit = manipulability_limit))
993 ic_sensor_name =
'rhsensor' 995 ic_sensor_name =
'rhsensor' 997 ic_sensor_name =
'lhsensor' 999 print 'startImpedance: argument must be rarm or larm.' 1001 self.ic_svc.deleteImpedanceControllerAndWait(ic_sensor_name)
1010 force_gain = [1, 1, 1],
1011 moment_gain = [0, 0, 0],
1014 reference_gain = 0.0,
1015 manipulability_limit = 0.1):
1017 @type arm: str name of artm to be controlled, this must be initialized 1018 using setSelfGroups() 1019 @param {force, moment}_gain: multipliers to the eef offset position 1020 vel_p and orientation vel_r. 3-dimensional 1021 vector (then converted internally into a 1024 self.ic_svc.setImpedanceControllerParam(
1026 OpenHRP.ImpedanceControllerService.impedanceParam(
1033 force_gain = force_gain,
1034 moment_gain = moment_gain,
1036 avoid_gain = avoid_gain,
1037 reference_gain = reference_gain,
1038 manipulability_limit = manipulability_limit))
1039 return self.ic_svc.startImpedanceController(arm)
1048 force_gain = [1, 1, 1],
1049 moment_gain = [0, 0, 0],
1052 reference_gain = 0.0,
1053 manipulability_limit = 0.1):
1055 @type arm: str name of artm to be controlled, this must be initialized 1056 using setSelfGroups() 1057 @param {force, moment}_gain: multipliers to the eef offset position 1058 vel_p and orientation vel_r. 3-dimensional 1059 vector (then converted internally into a 1062 r, p = self.ic_svc.getImpedanceControllerParam(arm)
1064 print(
'{}, impedance parameter not found for {}.'.format(self.configurator_name, arm))
1066 if M_p !=
None: p.M_p = M_p
1067 if D_p !=
None: p.M_p = D_p
1068 if K_p !=
None: p.M_p = K_p
1069 if M_r !=
None: p.M_r = M_r
1070 if D_r !=
None: p.M_r = D_r
1071 if K_r !=
None: p.M_r = K_r
1072 if force_gain !=
None: p.force_gain = force_gain
1073 if moment_gain !=
None: p.moment_gain = moment_gain
1074 if sr_gain !=
None: p.sr_gain = sr_gain
1075 if avoid_gain !=
None: p.avoid_gain = avoid_gain
1076 if reference_gain !=
None: p.reference_gain = reference_gain
1077 if manipulability_limit !=
None: p.manipulability_limit = manipulability_limit
1078 self.ic_svc.setImpedanceControllerParam(arm, p)
1079 return self.ic_svc.startImpedanceController(arm)
1082 return self.ic_svc.stopImpedanceController(arm)
1085 return self.ic_svc.stopImpedanceController(arm)
1089 Enable the ImpedanceController RT component. 1090 This method internally calls startImpedance-*, hrpsys version-specific 1093 @requires: ImpedanceController RTC to be activated on the robot's 1095 @param arm: Name of the kinematic group (i.e. self.Groups[n][0]). 1096 @param kwargs: This varies depending on the version of hrpsys your 1097 robot's controller runs on 1098 (which you can find by "self.hrpsys_version" command). 1099 For instance, if your hrpsys is 315.10.1, refer to 1100 "startImpedance_315_4" method. 1101 @change: (NOTE: This "change" block is a duplicate with the PR in the 1102 upstream https://github.com/fkanehiro/hrpsys-base/pull/1120. 1103 Once it gets merged this block should be removed to avoid 1104 duplicate maintenance effort.) 1106 From 315.2.0 onward, following arguments are dropped and can 1107 be set by self.seq_svc.setWrenches instead of this method. 1108 See an example at https://github.com/fkanehiro/hrpsys-base/pull/434/files#diff-6204f002204dd9ae80f203901f155fa9R44: 1109 - ref_force[fx, fy, fz] (unit: N) and 1110 ref_moment[tx, ty, tz] (unit: Nm) can be set via 1111 self.seq_svc.setWrenches. For example: 1113 self.seq_svc.setWrenches([0, 0, 0, 0, 0, 0, 1114 fx, fy, fz, tx, ty, tz, 1118 setWrenches takes 6 values per sensor, so the robot in 1119 the example above has 4 sensors where each line represents 1120 a sensor. See this link (https://github.com/fkanehiro/hrpsys-base/pull/434/files) for a concrete example. 1122 if StrictVersion(self.
hrpsys_version) < StrictVersion(
'315.2.0'):
1124 elif StrictVersion(self.
hrpsys_version) < StrictVersion(
'315.3.0'):
1131 if StrictVersion(self.
hrpsys_version) < StrictVersion(
'315.2.0'):
1133 elif StrictVersion(self.
hrpsys_version) < StrictVersion(
'315.3.0'):
1140 self.rh_svc.removeForceSensorOffset()
1145 angles = self.getJointAngles()
1150 if len(angles) != reduce(
lambda x,y: x+len(y[1]), self.
Groups, 0):
1154 for group
in self.
Groups:
1155 joint_num = len(group[1])
1156 angles.append(angles[index: index + joint_num])
1158 if group[0]
in [
'larm',
'rarm']:
1161 for i
in range(len(groups)):
1162 if groups[i][0] == limb:
1164 print self.configurator_name,
'could not find limb name ' + limb
1165 print self.configurator_name,
' in' + filter(
lambda x: x[0], groups)
1169 Clears the Sequencer's current operation for joint groups. 1172 if StrictVersion(self.seq_version) < StrictVersion(
'315.5.0'):
1173 raise RuntimeError(
'clearOfGroup is not available with your ' 1174 'software version ' + self.seq_version)
1175 HrpsysConfigurator.clearOfGroup(self, limb)
1177 print self.configurator_name,
'clearOfGroup(' + limb +
') will send ' + str(angles) +
' to update seqplay until https://github.com/fkanehiro/hrpsys-base/pull/1141 is available' 1178 self.setJointAnglesOfGroup(limb, angles, 0.1, wait=
True)
def hand_width2angles(self, width)
def goInitial(self, tm=7, wait=True, init_pose_type=0)
def init(self, robotname="HiroNX(Robot)0", url="")
def getReferencePose(self, lname=None, frame_name=None)
Returns the current commanded pose of the specified joint.
def goOffPose(self, tm=7)
def startImpedance(self, arm, kwargs)
def clearOfGroup(self, limb)
Clears the Sequencer's current operation for joint groups.
def setTargetPose(self, gname, pos, rpy, tm, frame_name=None)
Move the end-effector to the given absolute pose.
def setHandJointAngles(self, hand, angles, tm=1)
def stopImpedance_315_2(self, arm)
def servoOff(self, jname='all', wait=True)
def startImpedance_315_2(self, arm, M_p=100.0, D_p=100.0, K_p=100.0, M_r=100.0, D_r=2000.0, K_r=2000.0, force_gain=[1, moment_gain=[0, sr_gain=1.0, avoid_gain=0.0, reference_gain=0.0, manipulability_limit=0.1)
def isServoOn(self, jname='any')
def getJointAnglesOfGroup(self, limb)
def HandClose(self, hand=None, effort=None)
def getCurrentPose(self, lname=None, frame_name=None)
Returns the current physical pose of the specified joint.
def startImpedance_315_1(self, arm, M_p=100.0, D_p=100.0, K_p=100.0, M_r=100.0, D_r=2000.0, K_r=2000.0, ref_force=[0, force_gain=[1, ref_moment=[0, moment_gain=[0, sr_gain=1.0, avoid_gain=0.0, reference_gain=0.0, manipulability_limit=0.1)
def delete_module(modname, paranoid=None)
def stopImpedance_315_3(self, arm)
def stopImpedance_315_1(self, arm)
def servoOn(self, jname='all', destroy=1, tm=3)
def flat2Groups(self, flatList)
def HandOpen(self, hand=None, effort=None)
def startImpedance_315_3(self, arm, M_p=100.0, D_p=100.0, K_p=100.0, M_r=100.0, D_r=2000.0, K_r=2000.0, force_gain=[1, moment_gain=[0, sr_gain=1.0, avoid_gain=0.0, reference_gain=0.0, manipulability_limit=0.1)
def removeForceSensorOffset(self)
def _get_geometry(self, method, frame_name=None)
A method only inteded for class-internal usage.
def moveHand(self, hand, av, tm=1)
def checkEncoders(self, jname='all', option='')
def stopImpedance(self, arm)
tuple _MSG_IMPEDANCE_CALL_DONE
list _InitialPose_Factory
def setHandEffort(self, effort=100)
def setHandWidth(self, hand, width, tm=1, effort=None)