Merge branch 'master' into merge_upstream
This commit is contained in:
@@ -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)):
|
||||
@@ -347,7 +347,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,
|
||||
@@ -811,7 +810,10 @@ class HumanoidStablePD(object):
|
||||
rootPosSim, rootOrnSim = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
|
||||
rootPosKin, rootOrnKin = self._pybullet_client.getBasePositionAndOrientation(self._kin_model)
|
||||
linVelSim, angVelSim = self._pybullet_client.getBaseVelocity(self._sim_model)
|
||||
linVelKin, angVelKin = self._pybullet_client.getBaseVelocity(self._kin_model)
|
||||
#don't read the velocities from the kinematic model (they are zero), use the pose interpolator velocity
|
||||
#see also issue https://github.com/bulletphysics/bullet3/issues/2401
|
||||
linVelKin = self._poseInterpolator._baseLinVel
|
||||
angVelKin = self._poseInterpolator._baseAngVel
|
||||
|
||||
root_rot_err = self.calcRootRotDiff(rootOrnSim, rootOrnKin)
|
||||
pose_err += root_rot_w * root_rot_err
|
||||
|
||||
Reference in New Issue
Block a user