From 13937b80f8b131c1191720eb664e8fbde9b65410 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Fri, 17 Nov 2017 18:09:42 -0800 Subject: [PATCH 1/6] bump up version of pybullet to 1.6.7 --- setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/setup.py b/setup.py index 51ae4f5fa..81316647b 100644 --- a/setup.py +++ b/setup.py @@ -441,7 +441,7 @@ print("-----") setup( name = 'pybullet', - version='1.6.6', + version='1.6.7', 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', From 81146a4090982e593b7a1318c78622d974d456cf Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Sat, 18 Nov 2017 13:21:20 -0800 Subject: [PATCH 2/6] pybullet: move RGB,depth, segmentation mask preview windows to the right remove some dead code from PhysicsServerCommandProcessor.cpp --- .../Common2dCanvasInterface.h | 2 +- .../ExampleBrowser/OpenGLExampleBrowser.cpp | 13 +- .../PhysicsServerCommandProcessor.cpp | 259 +----------------- .../SharedMemory/PhysicsServerExample.cpp | 16 +- 4 files changed, 17 insertions(+), 273 deletions(-) diff --git a/examples/CommonInterfaces/Common2dCanvasInterface.h b/examples/CommonInterfaces/Common2dCanvasInterface.h index d531de2b1..b13dce97c 100644 --- a/examples/CommonInterfaces/Common2dCanvasInterface.h +++ b/examples/CommonInterfaces/Common2dCanvasInterface.h @@ -4,7 +4,7 @@ struct Common2dCanvasInterface { virtual ~Common2dCanvasInterface() {} - virtual int createCanvas(const char* canvasName, int width, int height)=0; + virtual int createCanvas(const char* canvasName, int width, int height, int xPos, int yPos)=0; virtual void destroyCanvas(int canvasId)=0; virtual void setPixel(int canvasId, int x, int y, unsigned char red, unsigned char green,unsigned char blue, unsigned char alpha)=0; virtual void getPixel(int canvasId, int x, int y, unsigned char& red, unsigned char& green,unsigned char& blue, unsigned char& alpha)=0; diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index d0d14b200..62cd73147 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -732,12 +732,11 @@ struct QuickCanvas : public Common2dCanvasInterface MyGraphWindow* m_gw[MAX_GRAPH_WINDOWS]; GraphingTexture* m_gt[MAX_GRAPH_WINDOWS]; int m_curNumGraphWindows; - int m_curXpos; + QuickCanvas(GL3TexLoader* myTexLoader) :m_myTexLoader(myTexLoader), - m_curNumGraphWindows(0), - m_curXpos(0) + m_curNumGraphWindows(0) { for (int i=0;igetInternalData()); input.m_width=width; input.m_height=height; - input.m_xPos = m_curXpos;//GUI will clamp it to the right//300; - m_curXpos+=width+20; - input.m_yPos = 10000;//GUI will clamp it to bottom + input.m_xPos = xPos; + input.m_yPos = yPos; input.m_name=canvasName; input.m_texName = canvasName; m_gt[slot] = new GraphingTexture; @@ -778,7 +776,6 @@ struct QuickCanvas : public Common2dCanvasInterface } virtual void destroyCanvas(int canvasId) { - m_curXpos = 0; btAssert(canvasId>=0); delete m_gt[canvasId]; m_gt[canvasId] = 0; diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 44ed1eb88..b96177ddc 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -60,9 +60,6 @@ #endif -//@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet! -btVector3 gLastPickPos(0, 0, 0); - int gInternalSimFlags = 0; bool gResetSimulation = 0; @@ -1604,49 +1601,6 @@ struct PhysicsServerCommandProcessorInternalData m_userVisualShapeHandles.exitHandles(); m_userVisualShapeHandles.initHandles(); -#if 0 - btAlignedObjectArray bla; - - for (int i=0;i<1024;i++) - { - int handle = allocHandle(); - bla.push_back(handle); - InternalBodyHandle* body = getHandle(handle); - InternalBodyData* body2 = body; - } - for (int i=0;im_enableTinyRenderer); bool loadOk = u2b.loadURDF(fileName, useFixedBase); - if (loadOk) { - -#if 1 btTransform rootTrans; rootTrans.setOrigin(pos); rootTrans.setRotation(orn); @@ -2762,188 +2713,11 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto if (m_data->m_sdfRecentLoadedBodies.size()==1) { *bodyUniqueIdPtr = m_data->m_sdfRecentLoadedBodies[0]; - } m_data->m_sdfRecentLoadedBodies.clear(); } return ok; -#else - - //get a body index - int bodyUniqueId = m_data->m_bodyHandles.allocHandle(); - if (bodyUniqueIdPtr) - *bodyUniqueIdPtr= bodyUniqueId; - - //quick prototype of 'save world' for crude world editing - { - SaveWorldObjectData sd; - sd.m_fileName = fileName; - sd.m_bodyUniqueIds.push_back(bodyUniqueId); - m_data->m_saveWorldBodyData.push_back(sd); - } - - u2b.setBodyUniqueId(bodyUniqueId); - InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(bodyUniqueId); - - - - { - btScalar mass = 0; - bodyHandle->m_rootLocalInertialFrame.setIdentity(); - btVector3 localInertiaDiagonal(0,0,0); - int urdfLinkIndex = u2b.getRootLinkIndex(); - u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,bodyHandle->m_rootLocalInertialFrame); - } - if (m_data->m_verboseOutput) - { - b3Printf("loaded %s OK!", fileName); - } - - btTransform tr; - tr.setIdentity(); - tr.setOrigin(pos); - tr.setRotation(orn); - //int rootLinkIndex = u2b.getRootLinkIndex(); - // printf("urdf root link index = %d\n",rootLinkIndex); - MyMultiBodyCreator creation(m_data->m_guiHelper); - - flags |= URDF_ORDER_TYPED_CONSTRAINT; - - ConvertURDF2Bullet(u2b,creation, tr,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix(),flags); - - for (int i=0;im_collisionShapes.push_back(shape); - } - - btMultiBody* mb = creation.getBulletMultiBody(); - btRigidBody* rb = creation.getRigidBody(); - - bodyHandle->m_bodyName = u2b.getBodyName(); - - if (useMultiBody) - { - - - if (mb) - { - mb->setUserIndex2(bodyUniqueId); - bodyHandle->m_multiBody = mb; - - if (flags & URDF_USE_SELF_COLLISION) - { - mb->setHasSelfCollision(true); - } - createJointMotors(mb); - -#ifdef B3_ENABLE_TINY_AUDIO - { - SDFAudioSource audioSource; - int urdfRootLink = u2b.getRootLinkIndex();//LinkIndex = creation.m_mb2urdfLink[-1]; - if (u2b.getLinkAudioSource(urdfRootLink,audioSource)) - { - int flags = mb->getBaseCollider()->getCollisionFlags(); - mb->getBaseCollider()->setCollisionFlags(flags | btCollisionObject::CF_HAS_COLLISION_SOUND_TRIGGER); - audioSource.m_userIndex = m_data->m_soundEngine.loadWavFile(audioSource.m_uri.c_str()); - if (audioSource.m_userIndex>=0) - { - bodyHandle->m_audioSources.insert(-1, audioSource); - } - } - } -#endif - - //serialize the btMultiBody and send the data to the client. This is one way to get the link/joint names across the (shared memory) wire - UrdfLinkNameMapUtil* util = new UrdfLinkNameMapUtil; - m_data->m_urdfLinkNameMapper.push_back(util); - util->m_mb = mb; - for (int i = 0; i < bufferSizeInBytes; i++) - { - bufferServerToClient[i] = 0;//0xcc; - } - util->m_memSerializer = new btDefaultSerializer(bufferSizeInBytes ,(unsigned char*)bufferServerToClient); - //disable serialization of the collision objects (they are too big, and the client likely doesn't need them); - util->m_memSerializer->m_skipPointers.insert(mb->getBaseCollider(),0); - - util->m_memSerializer->startSerialization(); - - - bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks()); - for (int i=0;igetNumLinks();i++) - { - int link=i; - //disable serialization of the collision objects - util->m_memSerializer->m_skipPointers.insert(mb->getLink(i).m_collider,0); - int urdfLinkIndex = creation.m_mb2urdfLink[i]; - btScalar mass; - btVector3 localInertiaDiagonal(0,0,0); - btTransform localInertialFrame; - u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,localInertialFrame); - bodyHandle->m_linkLocalInertialFrames.push_back(localInertialFrame); - - std::string* linkName = new std::string(u2b.getLinkName(urdfLinkIndex).c_str()); - m_data->m_strings.push_back(linkName); - util->m_memSerializer->registerNameForPointer(linkName->c_str(),linkName->c_str()); - mb->getLink(i).m_linkName = linkName->c_str(); - - std::string* jointName = new std::string(u2b.getJointName(urdfLinkIndex).c_str()); - m_data->m_strings.push_back(jointName); - util->m_memSerializer->registerNameForPointer(jointName->c_str(),jointName->c_str()); - mb->getLink(i).m_jointName = jointName->c_str(); -#ifdef B3_ENABLE_TINY_AUDIO - { - SDFAudioSource audioSource; - int urdfLinkIndex = creation.m_mb2urdfLink[link]; - if (u2b.getLinkAudioSource(urdfLinkIndex,audioSource)) - { - int flags = mb->getLink(link).m_collider->getCollisionFlags(); - mb->getLink(i).m_collider->setCollisionFlags(flags | btCollisionObject::CF_HAS_COLLISION_SOUND_TRIGGER); - audioSource.m_userIndex = m_data->m_soundEngine.loadWavFile(audioSource.m_uri.c_str()); - if (audioSource.m_userIndex>=0) - { - bodyHandle->m_audioSources.insert(link, audioSource); - } - } - } -#endif - } - - std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex())); - m_data->m_strings.push_back(baseName); - - mb->setBaseName(baseName->c_str()); - - util->m_memSerializer->registerNameForPointer(baseName->c_str(),baseName->c_str()); - - - - int len = mb->calculateSerializeBufferSize(); - btChunk* chunk = util->m_memSerializer->allocate(len,1); - const char* structType = mb->serialize(chunk->m_oldPtr, util->m_memSerializer); - util->m_memSerializer->finalizeChunk(chunk,structType,BT_MULTIBODY_CODE,mb); - - - - return true; - } else - { - b3Warning("No multibody loaded from URDF. Could add btRigidBody+btTypedConstraint solution later."); - return false; - } - - } else - { - if (rb) - { - bodyHandle->m_rigidBody = rb; - rb->setUserIndex2(bodyUniqueId); - return true; - } - } - #endif } - return false; } @@ -3017,14 +2791,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* for (int i=0;im_rigidBodyJoints.size();i++) { const btGeneric6DofSpring2Constraint* con = bodyHandle->m_rigidBodyJoints.at(i); -#if 0 - const btRigidBody& bodyA = con->getRigidBodyA(); - const btRigidBody& bodyB = con->getRigidBodyB(); - int len = bodyA.calculateSerializeBufferSize(); - btChunk* chunk = util->m_memSerializer->allocate(len,1); - const char* structType = bodyA.serialize(chunk->m_oldPtr, util->m_memSerializer); - util->m_memSerializer->finalizeChunk(chunk,structType,BT_RIGIDBODY_CODE,(void*)&bodyA); -#endif + util->m_memSerializer->registerNameForPointer(con,bodyHandle->m_rigidBodyJointNames[i].c_str()); util->m_memSerializer->registerNameForPointer(&con->getRigidBodyB(),bodyHandle->m_rigidBodyLinkNames[i].c_str()); @@ -3037,27 +2804,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* } streamSizeInBytes = util->m_memSerializer->getCurrentBufferSize(); -#if 0 - util->m_memSerializer->m_skipPointers.insert(mb->getBaseCollider(),0); - if (mb->getBaseName()) - { - util->m_memSerializer->registerNameForPointer(mb->getBaseName(),mb->getBaseName()); - } - bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks()); - for (int i=0;igetNumLinks();i++) - { - //disable serialization of the collision objects - util->m_memSerializer->m_skipPointers.insert(mb->getLink(i).m_collider,0); - util->m_memSerializer->registerNameForPointer(mb->getLink(i).m_linkName,mb->getLink(i).m_linkName); - util->m_memSerializer->registerNameForPointer(mb->getLink(i).m_jointName,mb->getLink(i).m_jointName); - } - util->m_memSerializer->registerNameForPointer(mb->getBaseName(),mb->getBaseName()); - int len = mb->calculateSerializeBufferSize(); - btChunk* chunk = util->m_memSerializer->allocate(len,1); - const char* structType = mb->serialize(chunk->m_oldPtr, util->m_memSerializer); - util->m_memSerializer->finalizeChunk(chunk,structType,BT_MULTIBODY_CODE,mb); - streamSizeInBytes = util->m_memSerializer->getCurrentBufferSize(); -#endif + } } @@ -8847,7 +8594,7 @@ bool PhysicsServerCommandProcessor::pickBody(const btVector3& rayFromWorld, cons { btVector3 pickPos = rayCallback.m_hitPointWorld; - gLastPickPos = pickPos; + btRigidBody* body = (btRigidBody*)btRigidBody::upcast(rayCallback.m_collisionObject); if (body) { diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 4f051e42b..32ce41d36 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -30,8 +30,8 @@ bool gActivedVRRealTimeSimulation = false; bool gEnableSyncPhysicsRendering= true; bool gEnableUpdateDebugDrawLines = true; -static int gCamVisualizerWidth = 320; -static int gCamVisualizerHeight = 240; +static int gCamVisualizerWidth = 228; +static int gCamVisualizerHeight = 192; static bool gEnableDefaultKeyboardShortcuts = true; static bool gEnableDefaultMousePicking = true; @@ -1751,9 +1751,9 @@ void PhysicsServerExample::initPhysics() { - m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",gCamVisualizerWidth, gCamVisualizerHeight); - m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",gCamVisualizerWidth, gCamVisualizerHeight); - m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",gCamVisualizerWidth, gCamVisualizerHeight); + m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",gCamVisualizerWidth, gCamVisualizerHeight, 8,55); + m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",gCamVisualizerWidth, gCamVisualizerHeight,8,75+gCamVisualizerHeight); + m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",gCamVisualizerWidth, gCamVisualizerHeight,8,95+gCamVisualizerHeight*2); for (int i=0;icreateCanvas("Synthetic Camera RGB data",gCamVisualizerWidth, gCamVisualizerHeight); + m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",gCamVisualizerWidth, gCamVisualizerHeight, 8,55); } } else { @@ -1922,7 +1922,7 @@ void PhysicsServerExample::updateGraphics() { if (m_canvasDepthIndex<0) { - m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",gCamVisualizerWidth, gCamVisualizerHeight); + m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",gCamVisualizerWidth, gCamVisualizerHeight,8,75+gCamVisualizerHeight); } } else { @@ -1940,7 +1940,7 @@ void PhysicsServerExample::updateGraphics() { if (m_canvasSegMaskIndex<0) { - m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",gCamVisualizerWidth, gCamVisualizerHeight); + m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",gCamVisualizerWidth, gCamVisualizerHeight,8,95+gCamVisualizerHeight*2); } } else { From 099a6f65f314dee885e61e221f5791586d8e9301 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Sat, 18 Nov 2017 15:18:46 -0800 Subject: [PATCH 3/6] tweak zbuffer visualization, show targetpos in example browser --- .../ExampleBrowser/OpenGLExampleBrowser.cpp | 2 +- .../SharedMemory/PhysicsServerExample.cpp | 24 +++++++++---------- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index 62cd73147..4fa27685c 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -1326,7 +1326,7 @@ void OpenGLExampleBrowser::update(float deltaTime) float camPos[3]; s_guiHelper->getRenderInterface()->getActiveCamera()->getCameraPosition(camPos); s_guiHelper->getRenderInterface()->getActiveCamera()->getCameraTargetPosition(camTarget); - sprintf(msg,"camPos=%f,%f,%f, dist=%f, pitch=%f, yaw=%f,target=%f,%f,%f", camPos[0],camPos[1],camPos[2],camDist,pitch,yaw,camTarget[0],camTarget[1],camTarget[2]); + sprintf(msg,"camTargetPos=%2.2f,%2.2f,%2.2f, dist=%2.2f, pitch=%2.2f, yaw=%2.2f", camPos[0],camPos[1],camPos[2],camDist,pitch,yaw); gui2->setStatusBarMessage(msg, true); } diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 32ce41d36..ebadcad29 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -2096,8 +2096,9 @@ void PhysicsServerExample::updateGraphics() int startSegIndex = m_multiThreadedHelper->m_startPixelIndex; int endSegIndex = startSegIndex + (*m_multiThreadedHelper->m_numPixelsCopied); - btScalar frustumZNear = m_multiThreadedHelper->m_projectionMatrix[14]/(m_multiThreadedHelper->m_projectionMatrix[10]-1); - btScalar frustumZFar = 20;//m_multiThreadedHelper->m_projectionMatrix[14]/(m_multiThreadedHelper->m_projectionMatrix[10]+1); + //btScalar frustumZNear = m_multiThreadedHelper->m_projectionMatrix[14]/(m_multiThreadedHelper->m_projectionMatrix[10]-1); + //btScalar frustumZFar = m_multiThreadedHelper->m_projectionMatrix[14]/(m_multiThreadedHelper->m_projectionMatrix[10]+1); + for (int i=0;i-1e20) { int rgb = 0; - btScalar minDepthValue = 0.98;//todo: compute more reasonably min/max depth range - btScalar maxDepthValue = 1; + btScalar frustumZNear = 0.1; + btScalar frustumZFar = 30; + btScalar minDepthValue = frustumZNear;//todo: compute more reasonably min/max depth range + btScalar maxDepthValue = frustumZFar; - if (maxDepthValue!=minDepthValue) - { - rgb = (depthValue-minDepthValue)*(255. / (btFabs(maxDepthValue-minDepthValue))); - if (rgb<0 || rgb>255) - { - //printf("rgb=%d\n",rgb); - } - } + float depth = depthValue; + double linearDepth = 255.*(2.0 * frustumZNear) / (frustumZFar + frustumZNear - depth * (frustumZFar - frustumZNear)); + btClamp(linearDepth, btScalar(0),btScalar(255)); + rgb = linearDepth; + m_canvas->setPixel(m_canvasDepthIndex,i,j, rgb, rgb, From 4226d57801e25ded91a6c7c6b3b16798d1a3edac Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sat, 18 Nov 2017 15:19:27 -0800 Subject: [PATCH 4/6] bump up pybullet version --- setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/setup.py b/setup.py index 81316647b..ae8e595b3 100644 --- a/setup.py +++ b/setup.py @@ -441,7 +441,7 @@ print("-----") setup( name = 'pybullet', - version='1.6.7', + version='1.6.8', 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', From c88132b80f59d1e06b527b6bc56a2b7e6f790bbc Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sat, 18 Nov 2017 17:07:27 -0800 Subject: [PATCH 5/6] fix issue in pybullet_envs.agents bump up to pybullet 1.6.9 --- examples/pybullet/gym/pybullet_envs/agents/__init__.py | 2 +- examples/pybullet/gym/pybullet_envs/agents/configs.py | 9 +++++++++ setup.py | 2 +- 3 files changed, 11 insertions(+), 2 deletions(-) diff --git a/examples/pybullet/gym/pybullet_envs/agents/__init__.py b/examples/pybullet/gym/pybullet_envs/agents/__init__.py index 9e2c9f092..c29ce33fe 100644 --- a/examples/pybullet/gym/pybullet_envs/agents/__init__.py +++ b/examples/pybullet/gym/pybullet_envs/agents/__init__.py @@ -20,4 +20,4 @@ from __future__ import print_function from . import train_ppo from . import utility -from . import visualize +from . import visualize_ppo diff --git a/examples/pybullet/gym/pybullet_envs/agents/configs.py b/examples/pybullet/gym/pybullet_envs/agents/configs.py index d613c29cb..a16fb1a62 100644 --- a/examples/pybullet/gym/pybullet_envs/agents/configs.py +++ b/examples/pybullet/gym/pybullet_envs/agents/configs.py @@ -119,6 +119,15 @@ def pybullet_racecar(): return locals() +def pybullet_humanoid(): + locals().update(default()) + randomizer = (minitaur_env_randomizer.MinitaurEnvRandomizer()) + env = 'HumanoidBulletEnv-v0' + max_length = 1000 + steps = 3e7 # 30M + return locals() + + def pybullet_minitaur(): """Configuration specific to minitaur_gym_env.MinitaurBulletEnv class.""" locals().update(default()) diff --git a/setup.py b/setup.py index ae8e595b3..a3ad02b43 100644 --- a/setup.py +++ b/setup.py @@ -441,7 +441,7 @@ print("-----") setup( name = 'pybullet', - version='1.6.8', + version='1.6.9', 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', From 88289c032ef7c6721df61e891d00682cb76b7a13 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sat, 18 Nov 2017 17:20:21 -0800 Subject: [PATCH 6/6] fix canvas issues from previous commit --- examples/RenderingExamples/RaytracerSetup.cpp | 2 +- examples/RenderingExamples/TimeSeriesCanvas.cpp | 2 +- examples/RenderingExamples/TinyVRGui.cpp | 2 +- examples/SharedMemory/PhysicsClientExample.cpp | 13 +++++++------ examples/SharedMemory/PhysicsServerExample.cpp | 2 +- 5 files changed, 11 insertions(+), 10 deletions(-) diff --git a/examples/RenderingExamples/RaytracerSetup.cpp b/examples/RenderingExamples/RaytracerSetup.cpp index 28d08fc9f..550451459 100644 --- a/examples/RenderingExamples/RaytracerSetup.cpp +++ b/examples/RenderingExamples/RaytracerSetup.cpp @@ -142,7 +142,7 @@ void RaytracerPhysicsSetup::initPhysics() if (m_internalData->m_canvas) { - m_internalData->m_canvasIndex = m_internalData->m_canvas->createCanvas("raytracer",m_internalData->m_width,m_internalData->m_height); + m_internalData->m_canvasIndex = m_internalData->m_canvas->createCanvas("raytracer",m_internalData->m_width,m_internalData->m_height, 15,55); for (int i=0;im_width;i++) { for (int j=0;jm_height;j++) diff --git a/examples/RenderingExamples/TimeSeriesCanvas.cpp b/examples/RenderingExamples/TimeSeriesCanvas.cpp index 096579839..60140b10e 100644 --- a/examples/RenderingExamples/TimeSeriesCanvas.cpp +++ b/examples/RenderingExamples/TimeSeriesCanvas.cpp @@ -78,7 +78,7 @@ TimeSeriesCanvas::TimeSeriesCanvas(struct Common2dCanvasInterface* canvasInterfa if (canvasInterface) { - m_internalData->m_canvasIndex = m_internalData->m_canvasInterface->createCanvas(windowTitle,m_internalData->m_width,m_internalData->m_height); + m_internalData->m_canvasIndex = m_internalData->m_canvasInterface->createCanvas(windowTitle,m_internalData->m_width,m_internalData->m_height,20,50); } } diff --git a/examples/RenderingExamples/TinyVRGui.cpp b/examples/RenderingExamples/TinyVRGui.cpp index 368606bf0..0b125dd33 100644 --- a/examples/RenderingExamples/TinyVRGui.cpp +++ b/examples/RenderingExamples/TinyVRGui.cpp @@ -28,7 +28,7 @@ struct TestCanvasInterface2 : public Common2dCanvasInterface virtual ~TestCanvasInterface2() {} - virtual int createCanvas(const char* canvasName, int width, int height) + virtual int createCanvas(const char* canvasName, int width, int height,int posX,int posY) { return 0; } diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index bdc65dac2..86aaa1a8a 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -22,8 +22,9 @@ struct MyMotorInfo2 int m_qIndex; }; -static int camVisualizerWidth = 320;//1024/3; -static int camVisualizerHeight = 240;//768/3; + +static int camVisualizerWidth = 228;//1024/3; +static int camVisualizerHeight = 192;//768/3; enum CustomCommands { @@ -758,10 +759,10 @@ void PhysicsClientExample::initPhysics() m_canvas = m_guiHelper->get2dCanvasInterface(); if (m_canvas) { - - m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",camVisualizerWidth, camVisualizerHeight); - m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",camVisualizerWidth, camVisualizerHeight); - m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",camVisualizerWidth, camVisualizerHeight); + m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",camVisualizerWidth, camVisualizerHeight, 8,55); + m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",camVisualizerWidth, camVisualizerHeight,8,75+camVisualizerHeight); + m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",camVisualizerWidth, camVisualizerHeight,8,95+camVisualizerHeight*2); + for (int i=0;i