From cd231c030e267389b66b45e544864fe7c924a1f0 Mon Sep 17 00:00:00 2001 From: Jeffrey Bingham Date: Wed, 27 Sep 2017 22:35:02 -0700 Subject: [PATCH] more formatting. --- examples/pybullet/examples/jacobian.py | 11 +++-------- examples/pybullet/pybullet.c | 12 ++++++------ 2 files changed, 9 insertions(+), 14 deletions(-) diff --git a/examples/pybullet/examples/jacobian.py b/examples/pybullet/examples/jacobian.py index e52caccdf..17638bfb3 100644 --- a/examples/pybullet/examples/jacobian.py +++ b/examples/pybullet/examples/jacobian.py @@ -1,5 +1,3 @@ -import sys -sys.path.append('/Users/bingjeff/Documents/projects/walkman/bullet3/bin/') import pybullet as p @@ -14,12 +12,9 @@ def setJointPosition(robot, position, kp=1.0, kv=0.3): num_joints = p.getNumJoints(robot) zero_vec = [0.0] * num_joints if len(position) == num_joints: - p.setJointMotorControlArray(robot, range(num_joints), - p.POSITION_CONTROL, - targetPositions=position, - targetVelocities=zero_vec, - positionGains=[kp] * num_joints, - velocityGains=[kv] * num_joints) + p.setJointMotorControlArray(robot, range(num_joints), p.POSITION_CONTROL, + targetPositions=position, targetVelocities=zero_vec, + positionGains=[kp] * num_joints, velocityGains=[kv] * num_joints) else: print("Not setting torque. " "Expected torque vector of " diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index f21d294c3..b332ad650 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -7411,12 +7411,12 @@ static PyMethodDef SpamMethods[] = { "Get the state (position, velocity etc) for multiple joints on a body."}, {"getLinkState", (PyCFunction)pybullet_getLinkState, METH_VARARGS | METH_KEYWORDS, - "position_linkcom_world, world_rotation_linkcom, " - "position_linkcom_frame, frame_rotation_linkcom, " - "position_frame_world, world_rotation_frame, " - "linearVelocity_linkcom_world, angularVelocity_linkcom_world = " - "getLinkState(objectUniqueId, linkIndex, computeLinkVelocity=0, " - "computeForwardKinematics=0, physicsClientId=0)\n" + "position_linkcom_world, world_rotation_linkcom,\n" + "position_linkcom_frame, frame_rotation_linkcom,\n" + "position_frame_world, world_rotation_frame,\n" + "linearVelocity_linkcom_world, angularVelocity_linkcom_world\n" + " = getLinkState(objectUniqueId, linkIndex, computeLinkVelocity=0,\n" + " computeForwardKinematics=0, physicsClientId=0)\n" "Provides extra information such as the Cartesian world coordinates" " center of mass (COM) of the link, relative to the world reference" " frame."},