Skip to content

Commit

Permalink
add a PR2 IK demo
Browse files Browse the repository at this point in the history
  • Loading branch information
rdeits committed Mar 2, 2016
1 parent c17a748 commit eb64b49
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 0 deletions.
1 change: 1 addition & 0 deletions drake/bindings/python/.gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,4 @@
pydrake/rbtree.py
pydrake/autodiffutils.py
pydrake/solvers/ik.py
*.pyc
28 changes: 28 additions & 0 deletions drake/bindings/python/pydrake/test/testPR2IK.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
import os
import numpy as np
import pydrake
from pydrake.solvers import ik

robot = pydrake.rbtree.RigidBodyTree(os.path.join(pydrake.getDrakePath(), "examples/PR2/pr2.urdf"))
print robot.bodies
print robot.bodies[0]

constraints = [ik.WorldPositionConstraint(robot, 1,
np.zeros((3,)),
np.array([0,0,1.0]),
np.array([0,0,1.0])),
ik.WorldPositionConstraint(robot, robot.findLink("r_gripper_palm_link").body_index,
np.zeros((3,)),
np.array([0.5,0,1.5]),
np.array([0.5,0,1.5])),
]
print constraints

q_seed = robot.getZeroConfiguration()
options = ik.IKoptions(robot)
results = ik.inverseKinSimple(robot, q_seed, q_seed, constraints, options)
print results
print repr(results.q_sol)


# print robot.getBody0()

0 comments on commit eb64b49

Please sign in to comment.