diff options
author | Darío Urbina <urbiname@usc.edu> | 2020-07-13 12:22:49 -0700 |
---|---|---|
committer | Darío Urbina <urbiname@usc.edu> | 2020-07-13 12:22:49 -0700 |
commit | 01d74be7775cc59080c2c9e9a26d0d9ddaef2091 (patch) | |
tree | d857eb16f86e5f9e3561c3ee84f89ee23dca0093 | |
parent | 6b6cfa6f03a54de484e15520f0a86ea81c9831ae (diff) | |
download | bullet3-01d74be7775cc59080c2c9e9a26d0d9ddaef2091.tar.gz |
Seeing the relatonship and understanding of the creation of two contraints
-rw-r--r-- | examples/pybullet/examples/constraint.py | 11 |
1 files changed, 11 insertions, 0 deletions
diff --git a/examples/pybullet/examples/constraint.py b/examples/pybullet/examples/constraint.py index 70d4a6fe9..9ba70028e 100644 --- a/examples/pybullet/examples/constraint.py +++ b/examples/pybullet/examples/constraint.py @@ -8,9 +8,17 @@ p.setAdditionalSearchPath(pybullet_data.getDataPath()) p.loadURDF("plane.urdf") cubeId = p.loadURDF("cube_small.urdf", 0, 0, 1) +cubeId2 = p.loadURDF("cube_small.urdf", 0, 0, 1) + p.setGravity(0, 0, -10) p.setRealTimeSimulation(1) + cid = p.createConstraint(cubeId, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], [0, 0, 1]) +cid2 = p.createConstraint(cubeId2, -1, cubeId, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], [0, 0, 1]) + +#cid2 = p.createConstraint(base_1, -1, base_2, 0, p.JOINT_FIXED, [0, 0, 0], [0, 0, 2], [0, 0, 0]) + + print(cid) print(p.getConstraintUniqueId(0)) prev = [0, 0, 1] @@ -22,7 +30,10 @@ while 1: time.sleep(.01) p.setGravity(0, 0, -10) pivot = [a, 0, 1] + pivot2 = [-a, 0, 1] orn = p.getQuaternionFromEuler([a, 0, 0]) p.changeConstraint(cid, pivot, jointChildFrameOrientation=orn, maxForce=50) + #p.changeConstraint(cid2, pivot2, jointChildFrameOrientation=orn, maxForce=50) + p.removeConstraint(cid) |