|
30 | 30 | from copy import deepcopy
|
31 | 31 |
|
32 | 32 | import rospy
|
33 |
| - |
| 33 | +from geometry_msgs.msg import PoseStamped |
34 | 34 | from sensor_msgs.msg import (
|
35 | 35 | JointState
|
36 | 36 | )
|
37 | 37 | from std_msgs.msg import (
|
38 | 38 | Float64,
|
| 39 | + Header |
39 | 40 | )
|
40 |
| - |
41 | 41 | import baxter_dataflow
|
42 | 42 |
|
43 | 43 | from baxter_core_msgs.msg import (
|
44 | 44 | JointCommand,
|
45 |
| - EndpointState, |
| 45 | + EndpointState |
| 46 | +) |
| 47 | +from baxter_core_msgs.srv import ( |
| 48 | + SolvePositionIK, |
| 49 | + SolvePositionIKRequest, |
46 | 50 | )
|
47 | 51 | from baxter_interface import settings
|
48 | 52 |
|
@@ -448,3 +452,50 @@ def joint_diff():
|
448 | 452 | raise_on_error=False,
|
449 | 453 | body=lambda: self.set_joint_positions(filtered_cmd())
|
450 | 454 | )
|
| 455 | + |
| 456 | + def ik(self, pose): |
| 457 | + ''' |
| 458 | + Call a ROS service PositionKinematicsNode/IKService to solve Baxter specific inverse kinematics. |
| 459 | + The code is based on http://sdk.rethinkrobotics.com/wiki/IK_Service_-_Code_Walkthrough |
| 460 | +
|
| 461 | + @param pose: Goal pose of the eef to compute ik for. |
| 462 | + @type pose: geometry_msgs.Pose |
| 463 | + @return: dict of position per joint. None if IK failed. |
| 464 | + @summary: Example output: |
| 465 | +
|
| 466 | + limb.get_eef_pose('left', pose) |
| 467 | + SUCCESS - Valid Joint Solution Found: |
| 468 | + [INFO] [WallTime: 1483757854.633608] [4312.677000] IK result: |
| 469 | + Out[9]: |
| 470 | + {'left_e0': 2.364365552432951, |
| 471 | + 'left_e1': 1.6132818021698665, |
| 472 | + 'left_s0': -0.5247314068347426, |
| 473 | + 'left_s1': 0.7952608492744296, |
| 474 | + 'left_w0': -2.7610159637242404, |
| 475 | + 'left_w1': 1.5973748950724531, |
| 476 | + 'left_w2': 0.37670722936273954} |
| 477 | + ''' |
| 478 | + limb = self.name |
| 479 | + |
| 480 | + ns = "ExternalTools/" + limb + "/PositionKinematicsNode/IKService" |
| 481 | + iksvc = rospy.ServiceProxy(ns, SolvePositionIK) |
| 482 | + ikreq = SolvePositionIKRequest() |
| 483 | + hdr = Header(stamp=rospy.Time.now(), frame_id='base') |
| 484 | + posestamped = PoseStamped() |
| 485 | + posestamped.header = hdr |
| 486 | + posestamped.pose = pose |
| 487 | + ikreq.pose_stamp.append(posestamped) |
| 488 | + try: |
| 489 | + rospy.wait_for_service(ns, 5.0) |
| 490 | + resp = iksvc(ikreq) |
| 491 | + except (rospy.ServiceException, rospy.ROSException), e: |
| 492 | + rospy.logerr("Service call failed: %s" % (e,)) |
| 493 | + return None |
| 494 | + if (resp.isValid[0]): |
| 495 | + rospy.loginfo("SUCCESS - Valid Joint Solution Found:") |
| 496 | + # Format solution into Limb API-compatible dictionary |
| 497 | + limb_joints = dict(zip(resp.joints[0].name, resp.joints[0].position)) |
| 498 | + rospy.loginfo('IK result: '.format(limb_joints)) |
| 499 | + else: |
| 500 | + rospy.logerr("INVALID POSE - No Valid Joint Solution Found.") |
| 501 | + return limb_joints |
0 commit comments