diff --git a/examples/pybullet/examples/jointFrictionDamping.py b/examples/pybullet/examples/jointFrictionDamping.py new file mode 100644 index 000000000..efe34e12f --- /dev/null +++ b/examples/pybullet/examples/jointFrictionDamping.py @@ -0,0 +1,28 @@ +import pybullet as p +import time + +p.connect(p.GUI) +p.loadURDF("plane.urdf",[0,0,-0.25]) +minitaur = p.loadURDF("quadruped/minitaur_single_motor.urdf",useFixedBase=True) +print(p.getNumJoints(minitaur)) +p.resetDebugVisualizerCamera(cameraDistance=1, cameraYaw=23.2, cameraPitch=-6.6,cameraTargetPosition=[-0.064,.621,-0.2]) +motorJointId = 1 +p.setJointMotorControl2(minitaur,motorJointId,p.VELOCITY_CONTROL,targetVelocity=100000,force=0) + +p.resetJointState(minitaur,motorJointId,targetValue=0, targetVelocity=1) +angularDampingSlider = p.addUserDebugParameter("angularDamping", 0,1,0) +jointFrictionForceSlider = p.addUserDebugParameter("jointFrictionForce", 0,0.1,0) + +textId = p.addUserDebugText("jointVelocity=0",[0,0,-0.2]) +p.setRealTimeSimulation(1) +while (1): + frictionForce = p.readUserDebugParameter(jointFrictionForceSlider) + angularDamping = p.readUserDebugParameter(angularDampingSlider) + p.setJointMotorControl2(minitaur,motorJointId,p.VELOCITY_CONTROL,targetVelocity=0,force=frictionForce) + p.changeDynamics(minitaur,motorJointId,linearDamping=0, angularDamping=angularDamping) + + time.sleep(0.01) + txt = "jointVelocity="+str(p.getJointState(minitaur,motorJointId)[1]) + prevTextId = textId + textId = p.addUserDebugText(txt,[0,0,-0.2]) + p.removeUserDebugItem(prevTextId) diff --git a/examples/pybullet/examples/testrender.py b/examples/pybullet/examples/testrender.py index 72fa9e27e..55eecd07c 100644 --- a/examples/pybullet/examples/testrender.py +++ b/examples/pybullet/examples/testrender.py @@ -3,6 +3,7 @@ import matplotlib.pyplot as plt import pybullet pybullet.connect(pybullet.GUI) +pybullet.loadURDF("plane.urdf") pybullet.loadURDF("r2d2.urdf") camTargetPos = [0.,0.,0.] @@ -18,8 +19,8 @@ pixelWidth = 320 pixelHeight = 240 nearPlane = 0.01 farPlane = 1000 -lightDirection = [0,1,0] -lightColor = [1,1,1]#optional argument +lightDirection = [0.4,0.4,0] +lightColor = [.3,.3,.3]#1,1,1]#optional argument fov = 60 #img_arr = pybullet.renderImage(pixelWidth, pixelHeight) @@ -30,7 +31,7 @@ for pitch in range (0,360,10) : aspect = pixelWidth / pixelHeight; projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane); #getCameraImage can also use renderer=pybullet.ER_BULLET_HARDWARE_OPENGL - img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightDirection,lightColor,renderer=pybullet.ER_TINY_RENDERER) + img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightAmbientCoeff = 0.3, lightDiffuseCoeff = 0.4, shadow=1, renderer=pybullet.ER_TINY_RENDERER) w=img_arr[0] h=img_arr[1] rgb=img_arr[2]