Skip to content

Commit 85826cc

Browse files
committed
1 parent aea70d9 commit 85826cc

File tree

1 file changed

+56
-3
lines changed

1 file changed

+56
-3
lines changed

src/baxter_interface/limb.py

+56-3
Original file line numberDiff line numberDiff line change
@@ -30,19 +30,23 @@
3030
from copy import deepcopy
3131

3232
import rospy
33-
33+
from geometry_msgs.msg import PoseStamped
3434
from sensor_msgs.msg import (
3535
JointState
3636
)
3737
from std_msgs.msg import (
3838
Float64,
39+
Header
3940
)
40-
4141
import baxter_dataflow
4242

4343
from baxter_core_msgs.msg import (
4444
JointCommand,
45-
EndpointState,
45+
EndpointState
46+
)
47+
from baxter_core_msgs.srv import (
48+
SolvePositionIK,
49+
SolvePositionIKRequest,
4650
)
4751
from baxter_interface import settings
4852

@@ -448,3 +452,52 @@ def joint_diff():
448452
raise_on_error=False,
449453
body=lambda: self.set_joint_positions(filtered_cmd())
450454
)
455+
456+
def ik(self, limb, pose):
457+
'''
458+
Call a ROS service PositionKinematicsNode/IKService to solve Baxter specific inverse kinematics.
459+
460+
@param limb: 'left' or 'right'
461+
@type limb: str
462+
@param pose:
463+
@type pose: geometry_msgs.Pose
464+
@return: dict of position per joint. None if IK failed.
465+
@summary: Example output:
466+
467+
limb.get_eef_pose('left', pose)
468+
SUCCESS - Valid Joint Solution Found:
469+
[INFO] [WallTime: 1483757854.633608] [4312.677000] IK result:
470+
Out[9]:
471+
{'left_e0': 2.364365552432951,
472+
'left_e1': 1.6132818021698665,
473+
'left_s0': -0.5247314068347426,
474+
'left_s1': 0.7952608492744296,
475+
'left_w0': -2.7610159637242404,
476+
'left_w1': 1.5973748950724531,
477+
'left_w2': 0.37670722936273954}
478+
'''
479+
limb = self.name
480+
481+
# Solve ik for the given Pose using http://sdk.rethinkrobotics.com/wiki/IK_Service_-_Code_Walkthrough
482+
ns = "ExternalTools/" + limb + "/PositionKinematicsNode/IKService"
483+
iksvc = rospy.ServiceProxy(ns, SolvePositionIK)
484+
ikreq = SolvePositionIKRequest()
485+
hdr = Header(stamp=rospy.Time.now(), frame_id='base')
486+
posestamped = PoseStamped()
487+
posestamped.header = hdr
488+
posestamped.pose = pose
489+
ikreq.pose_stamp.append(posestamped)
490+
try:
491+
rospy.wait_for_service(ns, 5.0)
492+
resp = iksvc(ikreq)
493+
except (rospy.ServiceException, rospy.ROSException), e:
494+
rospy.logerr("Service call failed: %s" % (e,))
495+
return None
496+
if (resp.isValid[0]):
497+
rospy.loginfo("SUCCESS - Valid Joint Solution Found:")
498+
# Format solution into Limb API-compatible dictionary
499+
limb_joints = dict(zip(resp.joints[0].name, resp.joints[0].position))
500+
rospy.loginfo('IK result: '.format(limb_joints))
501+
else:
502+
rospy.logerr("INVALID POSE - No Valid Joint Solution Found.")
503+
return limb_joints

0 commit comments

Comments
 (0)