diff --git a/Extras/Serialize/BulletFileLoader/btBulletFile.cpp b/Extras/Serialize/BulletFileLoader/btBulletFile.cpp index 18cb15321..aa1c383fd 100644 --- a/Extras/Serialize/BulletFileLoader/btBulletFile.cpp +++ b/Extras/Serialize/BulletFileLoader/btBulletFile.cpp @@ -128,6 +128,9 @@ void btBulletFile::parseData() mDataStart = 12; remain-=12; + //invalid/empty file? + if (remain < sizeof(bChunkInd)) + return; char *dataPtr = mFileBuffer+mDataStart; diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 5ab2e547f..22dad40ea 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -629,12 +629,13 @@ void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* colli textured_detailed_sphere_vertices[i*9+1], textured_detailed_sphere_vertices[i*9+2]); - btVector3 trVer = compound->getChildTransform(0)*(radiusScale*vert); + btVector3 trVer = (radiusScale*vert); if (trVer[up]>0) trVer[up]+=halfHeight; else trVer[up]-=halfHeight; + trVer = compound->getChildTransform(0)*trVer; transformedVertices[i*9+0] = trVer[0]; transformedVertices[i*9+1] = trVer[1]; diff --git a/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp b/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp index e8d43c8b1..b82d550a6 100644 --- a/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp +++ b/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp @@ -184,7 +184,6 @@ public: // return non-null if there is a status, nullptr otherwise virtual const struct SharedMemoryStatus* processServerStatus() { - printf("updating graphics!\n"); m_physicsServerExample->updateGraphics(); unsigned long long int curTime = m_clock.getTimeMicroseconds(); diff --git a/examples/pybullet/gym/pybullet_envs/env_bases.py b/examples/pybullet/gym/pybullet_envs/env_bases.py index 2d079e625..ef8ac0c5c 100644 --- a/examples/pybullet/gym/pybullet_envs/env_bases.py +++ b/examples/pybullet/gym/pybullet_envs/env_bases.py @@ -67,7 +67,11 @@ class MJCFBaseBulletEnv(gym.Env): self.isRender = True if mode != "rgb_array": return np.array([]) - base_pos = self.robot.body_xyz + + base_pos=[0,0,0] + if (hasattr(self,'robot')): + if (hasattr(self.robot,'body_xyz')): + base_pos = self.robot.body_xyz view_matrix = p.computeViewMatrixFromYawPitchRoll( cameraTargetPosition=base_pos, diff --git a/examples/pybullet/gym/pybullet_envs/robot_bases.py b/examples/pybullet/gym/pybullet_envs/robot_bases.py index 165ba8a09..e3b626adf 100644 --- a/examples/pybullet/gym/pybullet_envs/robot_bases.py +++ b/examples/pybullet/gym/pybullet_envs/robot_bases.py @@ -53,6 +53,7 @@ class MJCFBasedRobot: part_name = part_name.decode("utf8") parts[part_name] = BodyPart(part_name, bodies, i, -1) for j in range(p.getNumJoints(bodies[i])): + p.setJointMotorControl2(bodies[i],j,p.POSITION_CONTROL,positionGain=0.1,velocityGain=0.1,force=0) _,joint_name,_,_,_,_,_,_,_,_,_,_,part_name = p.getJointInfo(bodies[i], j) joint_name = joint_name.decode("utf8") @@ -209,4 +210,4 @@ class Joint: self.disable_motor() def disable_motor(self): - p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,controlMode=p.VELOCITY_CONTROL, force=0) + p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,controlMode=p.POSITION_CONTROL, targetPosition=0, targetVelocity=0, positionGain=0.1, velocityGain=0.1, force=0) diff --git a/examples/pybullet/gym/pybullet_envs/robot_pendula.py b/examples/pybullet/gym/pybullet_envs/robot_pendula.py index 0c82fea43..39c2c3878 100644 --- a/examples/pybullet/gym/pybullet_envs/robot_pendula.py +++ b/examples/pybullet/gym/pybullet_envs/robot_pendula.py @@ -19,7 +19,7 @@ class InvertedPendulum(MJCFBasedRobot): if not np.isfinite(a).all(): print("a is inf") a[0] = 0 - self.slider.set_motor_torque( 100*float(np.clip(a[0], -1, +1)) ) + self.slider.set_motor_torque( 100*float(np.clip(a[0], -1, +1)) ) def calc_state(self): self.theta, theta_dot = self.j1.current_position() @@ -81,4 +81,4 @@ class InvertedDoublePendulum(MJCFBasedRobot): self.pos_x, np.cos(theta), np.sin(theta), theta_dot, np.cos(gamma), np.sin(gamma), gamma_dot, - ]) \ No newline at end of file + ]) diff --git a/setup.py b/setup.py index b47b95c39..ecd208318 100644 --- a/setup.py +++ b/setup.py @@ -440,7 +440,7 @@ print("-----") setup( name = 'pybullet', - version='1.4.2', + version='1.4.5', description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.', url='https://github.com/bulletphysics/bullet3',