mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 21:30:09 +00:00
Merge pull request #2517 from erwincoumans/master
enable self-collision for deep_mimic pybullet_envs, fix Mac Catalina pybullet pip build
This commit is contained in:
commit
ef08e9b415
@ -1,8 +1,11 @@
|
||||
#ifndef B3_USE_GLFW
|
||||
#define __OBJC2__ 1
|
||||
#include <Foundation/NSExtensionContext.h>
|
||||
|
||||
#include "MacOpenGLWindowObjC.h"
|
||||
|
||||
#define GL_DO_NOT_WARN_IF_MULTI_GL_VERSION_HEADERS_INCLUDED
|
||||
|
||||
#import <Cocoa/Cocoa.h>
|
||||
#include "OpenGLInclude.h"
|
||||
|
||||
|
@ -84,32 +84,32 @@ p.addUserDebugText("Kinematic",
|
||||
p.addUserDebugText("Stable PD (Py)",
|
||||
[startLocations[4][0], startLocations[4][1] + 1, startLocations[4][2]],
|
||||
[0, 0, 0])
|
||||
|
||||
flags=p.URDF_MAINTAIN_LINK_ORDER+p.URDF_USE_SELF_COLLISION
|
||||
humanoid = p.loadURDF("humanoid/humanoid.urdf",
|
||||
startLocations[0],
|
||||
globalScaling=0.25,
|
||||
useFixedBase=False,
|
||||
flags=p.URDF_MAINTAIN_LINK_ORDER)
|
||||
flags=flags)
|
||||
humanoid2 = p.loadURDF("humanoid/humanoid.urdf",
|
||||
startLocations[1],
|
||||
globalScaling=0.25,
|
||||
useFixedBase=False,
|
||||
flags=p.URDF_MAINTAIN_LINK_ORDER)
|
||||
flags=flags)
|
||||
humanoid3 = p.loadURDF("humanoid/humanoid.urdf",
|
||||
startLocations[2],
|
||||
globalScaling=0.25,
|
||||
useFixedBase=False,
|
||||
flags=p.URDF_MAINTAIN_LINK_ORDER)
|
||||
flags=flags)
|
||||
humanoid4 = p.loadURDF("humanoid/humanoid.urdf",
|
||||
startLocations[3],
|
||||
globalScaling=0.25,
|
||||
useFixedBase=False,
|
||||
flags=p.URDF_MAINTAIN_LINK_ORDER)
|
||||
flags=flags)
|
||||
humanoid5 = p.loadURDF("humanoid/humanoid.urdf",
|
||||
startLocations[4],
|
||||
globalScaling=0.25,
|
||||
useFixedBase=False,
|
||||
flags=p.URDF_MAINTAIN_LINK_ORDER)
|
||||
flags=flags)
|
||||
|
||||
humanoid_fix = p.createConstraint(humanoid, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0],
|
||||
startLocations[0], [0, 0, 0, 1])
|
||||
|
@ -25,12 +25,12 @@ class HumanoidStablePD(object):
|
||||
self._mocap_data = mocap_data
|
||||
self._arg_parser = arg_parser
|
||||
print("LOADING humanoid!")
|
||||
|
||||
flags=self._pybullet_client.URDF_MAINTAIN_LINK_ORDER+self._pybullet_client.URDF_USE_SELF_COLLISION+self._pybullet_client.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS
|
||||
self._sim_model = self._pybullet_client.loadURDF(
|
||||
"humanoid/humanoid.urdf", [0, 0.889540259, 0],
|
||||
globalScaling=0.25,
|
||||
useFixedBase=useFixedBase,
|
||||
flags=self._pybullet_client.URDF_MAINTAIN_LINK_ORDER)
|
||||
flags=flags)
|
||||
|
||||
#self._pybullet_client.setCollisionFilterGroupMask(self._sim_model,-1,collisionFilterGroup=0,collisionFilterMask=0)
|
||||
#for j in range (self._pybullet_client.getNumJoints(self._sim_model)):
|
||||
@ -346,7 +346,6 @@ class HumanoidStablePD(object):
|
||||
#static char* kwlist[] = { "bodyUniqueId",
|
||||
#"jointIndices",
|
||||
#"controlMode", "targetPositions", "targetVelocities", "forces", "positionGains", "velocityGains", "maxVelocities", "physicsClientId", NULL };
|
||||
|
||||
self._pybullet_client.setJointMotorControlMultiDofArray(self._sim_model,
|
||||
indices,
|
||||
self._pybullet_client.STABLE_PD_CONTROL,
|
||||
|
@ -37,6 +37,8 @@ def build_arg_parser(args):
|
||||
arg_parser.load_args(args)
|
||||
|
||||
arg_file = arg_parser.parse_string('arg_file', '')
|
||||
if arg_file == '':
|
||||
arg_file = "run_humanoid3d_backflip_args.txt"
|
||||
if (arg_file != ''):
|
||||
path = pybullet_data.getDataPath() + "/args/" + arg_file
|
||||
succ = arg_parser.load_file(path)
|
||||
|
Loading…
Reference in New Issue
Block a user