summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorErwin Coumans <erwin.coumans@gmail.com>2019-12-12 07:02:27 -0800
committerErwin Coumans <erwin.coumans@gmail.com>2019-12-12 07:02:27 -0800
commit3668bc5e2aad6d47f6d844cd27660d7e215ba657 (patch)
tree0a9c130dbaab62af49956a2102cce4ec249c0dc0
parent1a491dc7007f000cf09f9f47eeb732832679f412 (diff)
downloadbullet3-3668bc5e2aad6d47f6d844cd27660d7e215ba657.tar.gz
tweak premake4 default batch file.
add manual control for joint angles in XArm6 example.
-rw-r--r--build_visual_studio_vr_pybullet_double.bat2
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/xarm.py25
2 files changed, 25 insertions, 2 deletions
diff --git a/build_visual_studio_vr_pybullet_double.bat b/build_visual_studio_vr_pybullet_double.bat
index e3e8a4dc5..b6fd3cb93 100644
--- a/build_visual_studio_vr_pybullet_double.bat
+++ b/build_visual_studio_vr_pybullet_double.bat
@@ -18,7 +18,7 @@ rem SET myvar=c:\python-3.5.2
cd build3
-premake4 --double --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
+premake4 --double --standalone-examples --enable_stable_pd --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
rem premake4 --double --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../binserver" vs2010
rem premake4 --double --enable_grpc --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../binserver" vs2010
diff --git a/examples/pybullet/gym/pybullet_envs/examples/xarm.py b/examples/pybullet/gym/pybullet_envs/examples/xarm.py
index 781d5afa4..893ff065e 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/xarm.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/xarm.py
@@ -1,7 +1,7 @@
import pybullet as p
import pybullet_data as pd
import time
-p.connect(p.GUI)
+p.connect(p.GUI)#, options="--background_color_red=1.0 --background_color_blue=1.0 --background_color_green=1.0")
p.setAdditionalSearchPath(pd.getDataPath())
@@ -14,7 +14,30 @@ table_pos = [0,0,-0.625]
table = p.loadURDF("table/table.urdf", table_pos, flags = flags, useFixedBase=useFixedBase)
xarm = p.loadURDF("xarm/xarm6_robot.urdf", flags = flags, useFixedBase=useFixedBase)
+jointIds = []
+paramIds = []
+
+for j in range(p.getNumJoints(xarm)):
+ p.changeDynamics(xarm, j, linearDamping=0, angularDamping=0)
+ info = p.getJointInfo(xarm, j)
+ #print(info)
+ jointName = info[1]
+ jointType = info[2]
+ if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE):
+ jointIds.append(j)
+ paramIds.append(p.addUserDebugParameter(jointName.decode("utf-8"), -4, 4, 0))
+
+skip_cam_frames = 10
+
while (1):
p.stepSimulation()
+ for i in range(len(paramIds)):
+ c = paramIds[i]
+ targetPos = p.readUserDebugParameter(c)
+ p.setJointMotorControl2(xarm, jointIds[i], p.POSITION_CONTROL, targetPos, force=5 * 240.)
+ skip_cam_frames -= 1
+ if (skip_cam_frames<0):
+ p.getCameraImage(320,200, renderer=p.ER_BULLET_HARDWARE_OPENGL )
+ skip_cam_frames = 10
time.sleep(1./240.)