Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
40
examples/pybullet/examples/biped2d_pybullet.py
Normal file
40
examples/pybullet/examples/biped2d_pybullet.py
Normal file
@@ -0,0 +1,40 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
import os
|
||||
import time
|
||||
GRAVITY = -9.8
|
||||
dt = 1e-3
|
||||
iters=2000
|
||||
|
||||
physicsClient = p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.resetSimulation()
|
||||
#p.setRealTimeSimulation(True)
|
||||
p.setGravity(0,0,GRAVITY)
|
||||
p.setTimeStep(dt)
|
||||
planeId = p.loadURDF("plane.urdf")
|
||||
cubeStartPos = [0,0,1.13]
|
||||
cubeStartOrientation = p.getQuaternionFromEuler([0.,0,0])
|
||||
botId = p.loadURDF("biped/biped2d_pybullet.urdf",
|
||||
cubeStartPos,
|
||||
cubeStartOrientation)
|
||||
|
||||
#disable the default velocity motors
|
||||
#and set some position control with small force to emulate joint friction/return to a rest pose
|
||||
jointFrictionForce=1
|
||||
for joint in range (p.getNumJoints(botId)):
|
||||
p.setJointMotorControl2(botId,joint,p.POSITION_CONTROL,force=jointFrictionForce)
|
||||
|
||||
#for i in range(10000):
|
||||
# p.setJointMotorControl2(botId, 1, p.TORQUE_CONTROL, force=1098.0)
|
||||
# p.stepSimulation()
|
||||
#import ipdb
|
||||
#ipdb.set_trace()
|
||||
import time
|
||||
p.setRealTimeSimulation(1)
|
||||
while (1):
|
||||
#p.stepSimulation()
|
||||
#p.setJointMotorControl2(botId, 1, p.TORQUE_CONTROL, force=1098.0)
|
||||
p.setGravity(0,0,GRAVITY)
|
||||
time.sleep(1/240.)
|
||||
time.sleep(1000)
|
||||
32
examples/pybullet/examples/otherPhysicsEngine.py
Normal file
32
examples/pybullet/examples/otherPhysicsEngine.py
Normal file
@@ -0,0 +1,32 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
#p.connect(p.DIRECT)
|
||||
#p.connect(p.DART)
|
||||
p.connect(p.MuJoCo)
|
||||
|
||||
#p.connect(p.GUI)
|
||||
bodies = p.loadMJCF("mjcf/capsule.xml")
|
||||
print("bodies=",bodies)
|
||||
|
||||
numBodies = p.getNumBodies()
|
||||
print("numBodies=",numBodies)
|
||||
for i in range (numBodies):
|
||||
print("bodyInfo[",i,"]=",p.getBodyInfo(i))
|
||||
|
||||
p.setGravity(0,0,-10)
|
||||
timeStep = 1./240.
|
||||
p.setPhysicsEngineParameter(fixedTimeStep=timeStep)
|
||||
|
||||
#while (p.isConnected()):
|
||||
for i in range (1000):
|
||||
p.stepSimulation()
|
||||
|
||||
for b in bodies:
|
||||
pos,orn=p.getBasePositionAndOrientation(b)
|
||||
print("pos[",b,"]=",pos)
|
||||
print("orn[",b,"]=",orn)
|
||||
linvel,angvel=p.getBaseVelocity(b)
|
||||
print("linvel[",b,"]=",linvel)
|
||||
print("angvel[",b,"]=",angvel)
|
||||
time.sleep(timeStep)
|
||||
273
examples/pybullet/gym/pybullet_data/biped/biped2d_pybullet.urdf
Normal file
273
examples/pybullet/gym/pybullet_data/biped/biped2d_pybullet.urdf
Normal file
@@ -0,0 +1,273 @@
|
||||
|
||||
|
||||
|
||||
<?xml version="1.0"?>
|
||||
<robot name="balance">
|
||||
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0.2 0.2 0.2 1"/>
|
||||
</material>
|
||||
|
||||
<material name="blue">
|
||||
<color rgba="0 0 1 1"/>
|
||||
</material>
|
||||
|
||||
<link name="world">
|
||||
<inertial>
|
||||
<mass value="0"/>
|
||||
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="y_prismatic">
|
||||
<inertial>
|
||||
<mass value="0.01"/>
|
||||
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="y_to_world" type="prismatic">
|
||||
<parent link="world"/>
|
||||
<child link="y_prismatic"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="0.0" lower="1" upper="-1" velocity="1000.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="z_prismatic">
|
||||
<inertial>
|
||||
<mass value="0.01"/>
|
||||
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="z_to_y" type="prismatic">
|
||||
<parent link="y_prismatic"/>
|
||||
<child link="z_prismatic"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="0.0" lower="1" upper="-1" velocity="1000.0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<joint name="torso_to_z" type="continuous">
|
||||
<parent link="z_prismatic"/>
|
||||
<child link="torso"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 1.4"/>
|
||||
</joint>
|
||||
|
||||
<link name="torso">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.1 0.1 0.48"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0.0 0"/>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.1 0.1 0.48"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0.0 0"/>
|
||||
<contact_coefficients mu="0.08" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="70"/>
|
||||
<inertia ixx="0.2404" ixy="-0.01" ixz="-0.048" iyy="0.2404" iyz="-0.048" izz="0.02"/>
|
||||
<origin rpy="0 0 0" xyz="0 0.0 0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="r_upperleg">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.1 .45"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0.018 0. -0.21715"/>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.05 0.1 .45"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0.018 -0.0 -0.21715"/>
|
||||
<contact_coefficients mu="0.08" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="5"/>
|
||||
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
|
||||
<origin rpy="0 0 0" xyz="0.018 -0 -0.21715"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
|
||||
<joint name="torso_to_rightleg" type="revolute">
|
||||
<parent link="torso"/>
|
||||
<child link="r_upperleg"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="0.0" lower="-1.57." upper="1.57" velocity="1000.0"/>
|
||||
<origin rpy="0 0 0" xyz="0.05 0 -0.17"/>
|
||||
</joint>
|
||||
|
||||
<link name="l_upperleg">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.1 .45"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="-0.018 0. -0.21715"/>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.05 0.1 .45"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="-0.018 0.0 -0.21715"/>
|
||||
<contact_coefficients mu="0.08" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="5"/>
|
||||
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
|
||||
<origin rpy="0 0 0" xyz="-0.018 -0 -0.21715"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
|
||||
<joint name="torso_to_leftleg" type="revolute">
|
||||
<parent link="torso"/>
|
||||
<child link="l_upperleg"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="10.0" lower="-1.57." upper="1.57" velocity="1000.0"/>
|
||||
<origin rpy="0 0 0" xyz="-0.05 0 -0.17"/>
|
||||
</joint>
|
||||
|
||||
<link name="r_lowerleg">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.1 .45"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0.048 0. -0.21715"/>
|
||||
<material name="blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.05 0.1 .45"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0.048 0.0 -0.21715"/>
|
||||
<contact_coefficients mu="0.08" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
|
||||
<origin rpy="0 0 0" xyz="0.048 -0 -0.21715"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
|
||||
<joint name="r_knee" type="revolute">
|
||||
<parent link="r_upperleg"/>
|
||||
<child link="r_lowerleg"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="10.0" lower="-1.57." upper="1.57" velocity="1000.0"/>
|
||||
<origin rpy="0 0 0" xyz="0.015 0 -.41"/>
|
||||
</joint>
|
||||
|
||||
<link name="l_lowerleg">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.1 .45"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="-0.048 0. -0.21715"/>
|
||||
<material name="blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.1 0.1 .45"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="-0.048 0.0 -0.21715"/>
|
||||
<contact_coefficients mu="0.08" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
|
||||
<origin rpy="0 0 0" xyz="-0.048 -0 -0.21715"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
|
||||
<joint name="l_knee" type="revolute">
|
||||
<parent link="l_upperleg"/>
|
||||
<child link="l_lowerleg"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="10.0" lower="-1.57." upper="1.57" velocity="1000.0"/>
|
||||
<origin rpy="0 0 0" xyz="-0.015 0 -.41"/>
|
||||
</joint>
|
||||
|
||||
<link name="l_foot">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.2 .04"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0.05 0.08 -0.038"/>
|
||||
<material name="blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.05 0.2 .04"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0.05 0.08 -0.038"/>
|
||||
<contact_coefficients mu="0.5" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="1"/>
|
||||
<inertia ixx="0.0416" ixy="-0.01" ixz="-0.002" iyy="0.0041" iyz="-0.008" izz="0.0425"/>
|
||||
<origin rpy="0 0 0" xyz="0.05 0.08 -0.038"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="l_ankle" type="revolute">
|
||||
<parent link="l_lowerleg"/>
|
||||
<child link="l_foot"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="10.0" lower="-2" upper="2" velocity="1000.0"/>
|
||||
<origin rpy="0 0 0" xyz="-0.05 -0.03 -.459"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<link name="r_foot">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.2 .04"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="-0.05 0.08 -0.038"/>
|
||||
<material name="blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.05 0.2 .04"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="-0.05 0.08 -0.038"/>
|
||||
<contact_coefficients mu="0.5" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="1"/>
|
||||
<inertia ixx="0.0416" ixy="-0.01" ixz="-0.002" iyy="0.0041" iyz="-0.008" izz="0.0425"/>
|
||||
<origin rpy="0 0 0" xyz="-0.05 0.08 -0.038"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="r_ankle" type="revolute">
|
||||
<parent link="r_lowerleg"/>
|
||||
<child link="r_foot"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="10.0" lower="-2." upper="2" velocity="1000.0"/>
|
||||
<origin rpy="0 0 0" xyz="0.05 -0.03 -.459"/>
|
||||
</joint>
|
||||
|
||||
</robot>
|
||||
@@ -5,6 +5,14 @@
|
||||
#include "../SharedMemory/PhysicsClientUDP_C_API.h"
|
||||
#endif //BT_ENABLE_ENET
|
||||
|
||||
#ifdef BT_ENABLE_DART
|
||||
#include "../SharedMemory/dart/DARTPhysicsC_API.h"
|
||||
#endif
|
||||
|
||||
#ifdef BT_ENABLE_MUJOCO
|
||||
#include "../SharedMemory/mujoco/MuJoCoPhysicsC_API.h"
|
||||
#endif
|
||||
|
||||
#ifdef BT_ENABLE_CLSOCKET
|
||||
#include "../SharedMemory/PhysicsClientTCP_C_API.h"
|
||||
#endif //BT_ENABLE_CLSOCKET
|
||||
@@ -407,6 +415,22 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
sm = b3ConnectPhysicsDirect();
|
||||
break;
|
||||
}
|
||||
#ifdef BT_ENABLE_DART
|
||||
case eCONNECT_DART:
|
||||
{
|
||||
sm = b3ConnectPhysicsDART();
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef BT_ENABLE_MUJOCO
|
||||
case eCONNECT_MUJOCO:
|
||||
{
|
||||
sm = b3ConnectPhysicsMuJoCo();
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
case eCONNECT_SHARED_MEMORY:
|
||||
{
|
||||
sm = b3ConnectSharedMemory(key);
|
||||
@@ -9558,6 +9582,14 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "GUI_SERVER", eCONNECT_GUI_SERVER); // user read
|
||||
PyModule_AddIntConstant(m, "GUI_MAIN_THREAD", eCONNECT_GUI_MAIN_THREAD); // user read
|
||||
PyModule_AddIntConstant(m, "SHARED_MEMORY_SERVER", eCONNECT_SHARED_MEMORY_SERVER); // user read
|
||||
#ifdef BT_ENABLE_DART
|
||||
PyModule_AddIntConstant(m, "DART", eCONNECT_DART); // user read
|
||||
#endif
|
||||
|
||||
#ifdef BT_ENABLE_MUJOCO
|
||||
PyModule_AddIntConstant(m, "MuJoCo", eCONNECT_MUJOCO); // user read
|
||||
#endif
|
||||
|
||||
|
||||
PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY", SHARED_MEMORY_KEY);
|
||||
PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY2", SHARED_MEMORY_KEY+1);
|
||||
|
||||
Reference in New Issue
Block a user