allow btMultiBody to not wakeup (for some RL experiments)
move deep_mimic motion files to data/motions folder, so we can use the args files unmodified.
expose minGraphicsUpdateTimeMs through PyBullet.connect(p.GUI, options="minGraphicsUpdateTimeMs=32000"), by default OpenGL rendering runs at 4000microseconds intervals.
allow a maximum of 128k objects
fix meshScale for PyBullet.createCollisionShape for custom mesh
expose Pybullet.setPhysicsEngineParameter(minimumSolverIslandSize=...), larger minimum batches group solver constraints together in the same island, to reduce calling overhead (even if they are not related)
When using the USER_DATA_ADDED and USER_DATA_REMOVED notifications, some
more information is necessary than just the user data id, especially
when a user data entry has been removed.
PyBullet: Implement a few more APIs of PhysX backend, resetJointState and setJointMotorControl2
allow useMaximalCoordinate=True for PhysX loadURDF (only for single rigid bodies, articulations require reduced coordinates at the moment)
Add inverse dynamics / mass matrix code from DeepMimic, thanks to Xue Bin (Jason) Peng
Add example how to use stable PD control for humanoid with spherical joints (see humanoidMotionCapture.py)
Fix related to TinyRenderer object transforms not updating when using collision filtering
See createMesh.py for an example.
The data has to fit in shared memory, hence the limit on Mac is lower than Windows and Linux:
#ifdef __APPLE__
#define B3_MAX_NUM_VERTICES 8192
#define B3_MAX_NUM_INDICES 32768
#else
#define B3_MAX_NUM_VERTICES 131072
#define B3_MAX_NUM_INDICES 524288
#endif
Using calculateInverseDynamics with zero target acceleration allows to compute the non-linear dynamics forces (coriolis/gyroscopic) and/or gravity force.
Add preparation for DeepMimic humanoid environment, replicating parts of https://github.com/xbpeng/DeepMimic
Loading humanoid.urdf and applying motion action: examples/pybullet/gym/pybullet_envs/mimic/humanoid.py
Loading MotionCapture data: examples/pybullet/gym/pybullet_envs/mimic/motion_capture_data.py
Little test: examples/pybullet/gym/pybullet_envs/mimic/humanoid_test.py
Expose this btMultiBodySphericalJointMotor through PyBullet.setJointMotorControlMultiDof
Expose PyBullet.getQuaternionSlerp
Improve PyBullet.setJointMotorControlMultiDof
Improve humanoidMotionCapture.py with slerp and using setJointMotorControlMultiDof
Expose btMultiBody::spatialTransform
Fix btMultiBody::setupPlanar from DeepMimic codebase
Add support for multidof joints in btMultiBody::compTreeLinkVelocities, thanks to DeepMimic codebase @xbpeng
See createObstacleCourse.py for an example use. At the moment a limit of 1024 vertices and 1024 indices.
Will be lifted once we implement the streaming version (soon).
b3InitUpdateVisualShape doesn't take textureUniqueId by default. new API b3UpdateVisualShapeTexture to change texture (-1 will clear texture)
PyBullet/BulletRobotics: allow to reset the textureUniqueId to -1, to clear a texture
PyBullet/BulletRobotics: save all texture handles
enable follow cam in other Gym locomotion environments
add testing assets for multi-material obj files -> sdf conversion.
Also use ER_NO_SEGMENTATION_MASK flag for TinyRenderer/EGL plugin renderer
Support SDF loading through fileIO plugin.
Replace strcspn by C code (not crossplatform)
Add flag for loadURDF to use color from MTL file (instead from URDF link material)
pybullet.URDF_USE_MATERIAL_COLORS_FROM_MTL and pybullet.URDF_USE_MATERIAL_TRANSPARANCY_FROM_MTL
If parentObjectUniqueId provided, convert local from/to into world space coordinates
AddUserDebugLins: don't block when replacing an item
Fix examples/pybullet/examples/inverse_kinematics.py
A fileIO plugin can override custom file IO operations. As a small test, load files from a zipfile in memory.
Default fileIO implementation is in examples/Utils/b3BulletDefaultFileIO.h
Affects URDF, SDF, MJCF, Wavefront OBJ, STL, DAE, images.
PyBullet Allow OpenGL/EGL hardware to render segmentation mask. Use pybullet.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX or pybullet.ER_SEGMENTATION_MASK
PyBullet.removeBody fix indexing bug (use foundIndex, not i)
PyBullet bump up version to 2.2.3
Apply clang-format-all.sh using the _clang-format file through all the cpp/.h files.
make sure not to apply it to certain serialization structures, since some parser expects the * as part of the name, instead of type.
This commit contains no other changes aside from adding and applying clang-format-all.sh
allow to perform a getClosestPoints query with a collisionShape and world transform (position, orientation) that isn't part of the world.
(use createCollisionShape to create it)
add optional removeCollisionShape, for collision shapes only used in a query (and not used to create a body)
allow to perform a getClosestPoints query with a collisionShape and world transform (position, orientation) that isn't part of the world.
(use createCollisionShape to create it)
while (1):
stepSimulation()
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_SINGLE_STEP_RENDERING, 1)
disable single step using
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_SINGLE_STEP_RENDERING, 0)
Implement collisionFilterPlugin, use setCollisionFilterPair to enable or disable collision detection between specific pairs of objects.
Also, expose setCollisionFilterGroupMask as PyBullet API and in urdf using the tag <collision group="1" mask="2"/>.
See examples/pybullet/examples/collisionFilter.py for an example.
PyBullet default: Lower the warmstarting factor, for maximal coordinates rigid bodies for more stable simulation.
Add btCollisionWorld::refreshBroadphaseProxy to easier recreate the broadphase proxy without adding/removing objects to the world.
Changes the b3GetLinkState function to use numLinks from the
SharedMemoryStatus returned from RequestActualState instead of the
cached number of link value returned by b3GetNumJoints.
The cached value can be outdated when a new body is added and
SyncBodyInfo isn't used, while using the value in the status is always
up-to-date.
move setup.py back to eglRenderer extension, use pkgutil.get_loader('eglRenderer').get_filename()
disable dlmopen by default, unless B3_USE_DLMOPEN is defined.
just use pybullet.loadPlugin("eglRendererPlugin") before loading/creating any objects.
use end/startRendering (swap buffers) before the rendering in the eglPlugin
postpone the 'loadPlugin' for static eglPlugin, so that the init and exit happen in the same thread.
When you don't call unloadPlugin, the program may crash when exiting in SHARED_MEMORY_SERVER mode.
add grpcPlugin, it can work in GUI, SHARED_MEMORY_SERVER, DIRECT and other modes.
example script to start server from pybullet:
import pybullet as p
p.connect(p.GUI)
#if statically linked plugin
id = p.loadPlugin("grpcPlugin")
#dynamics loading the plugin
#id = p.loadPlugin("E:/develop/bullet3/bin/pybullet_grpcPlugin_vs2010_x64_debug.dll", postFix="_grpcPlugin")
#start the GRPC server at hostname, port
if (id>=0):
p.executePluginCommand(id, "localhost:1234")
Only in DIRECT mode, since there is no 'ping' you need to call to handle RCPs:
numRPC = 10
while (1):
p.executePluginCommand(id, intArgs=[numRPC])
Problem description:
When you add a body, remove it and then add a new
body, the body id may be reused by Bullet.
Because the visual shape data was not being removed when a body was
removed, requesting the visual shape data for a 'recycled' body id
results in both the visual shape data of the new body as well as the old
one.
Removing the visual shape data when the body gets removed fixes this.
Changes the btAlignedObjectArray for visual shapes to a hashmap, so
that removing is faster. Additionally, functions like getNumVisualShape
don't perform a linear search anymore.
Will add GRPC client and PyBullet GRPC server plugin.
Will cover most/all SharedMemoryCommand/SharedMemoryStatus messages.
Run the server, then test using the pybullet_client.py
This avoids issues with systems with large mass ratios.
Test: add this to BasicDemo/BasicExample.cpp in initPhysics
m_dynamicsWorld->getSolverInfo().m_numIterations = 1000;
m_dynamicsWorld->getSolverInfo().m_leastSquaresResidualThreshold = 1e-4;
This removes the need to specify the body id/link index when retrieving a user data entry.
Additionally, user data can now optionally be set to visual shapes as well.
The following public pybullet APIs have changed (backwards incompatible)
addUserData and getUserDataId
Makes linkIndex parameter optional (default value is -1)
Adds optional visualShapeIndex parameter (default value is -1)
getUserData and removeUserData
Removes required parameters bodyUniqueId and linkIndex
getNumUserData
Removes required bodyUniqueId parameter
getUserDataInfo
Removes required linkIndex parameter
Changes returned tuple from (userDataId, key) to (userDataId, key, bodyUniqueId, linkIndex, visualShapeIndex)
- Limits the maximum number of threads to 64, since btThreadSupportPosix
and btThreadsupportWin32 don't support more than 64 bits at this moment,
due to the use of UINT64 bitmasks. This could be fixed by using
std::bitset or some other alternative.
- Introduces a threadpool class, b3ThreadPool, which is a simple wrapper
around btThreadSupportInterface and uses this instead of the global task
scheduler for parallel raycasting. This is actually quite a bit faster
than the task scheduler (~10-15% in my tests for parallel raycasts),
since the advanced features (parallelFor) are not necessary for the
parallel raycasts.
- Puts 16*1024 of MAX_RAY_INTERSECTION_MAX_SIZE_STREAMING in
parentheses, since it otherwise causes problems with other operators
of equal precedence and introduces a smaller constant for Apple targets.
- Refactors the parallel raycasts code and adds some more profiling.
use b3RaycastBatchAddRays API to enable MAX_RAY_INTERSECTION_BATCH_SIZE_STREAMING num rays.
Old API (b3RaycastBatchAddRay) sticks to 256 rays, MAX_RAY_INTERSECTION_BATCH_SIZE.
(and issue with TaskScheduler/btTaskScheduler.cpp, add JobQueue::exit, call it first, since it uses the m_threadSupport which was deleted before the destrucor was called.
Use a hashmap to store user timers, to avoid allocating many identical strings.
reduce 'm_cooldownTime' from 1000 microseconds to 100 microseconds (overhead in raycast is too large)
If needed, we can expose this cooldown time.
Replace malloc by btAlignedObjectArray (going through Bullet's memory allocator)
To enable the feature, enable the BULLET2_MULTITHREADING option.
Increases the number of rays that can go in a batch request by storing
them in the shared memory stream instead of the shared memory command.
Adds the API b3RaycastBatchSetNumThreads to specify the number of
threads to use for the raycast batch, also adds the argument numThreads
to the pybullet function rayTestBatch.
Rays are distributed among the threads in a greedy fashion there's a shared
queue of work, once a thread finishes its task, it picks the next
available ray from the task. This works better than pre-distributing the
rays among threads, since there's a large variance in computation time per ray.
Some controversial changes:
- Added a pointer to PhysicsClient to the SharedMemoryCommand struct, this
was necessary to keep the C-API the same for b3RaycastBatchAddRay, while
adding the ray to the shared memory stream instead of the command
struct. I think this may be useful to simplify other APIs as well, that
take both a client handle and a command handle.
- Moved #define SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE to
SharedMemoryPublic. This was necessary for the definition of
MAX_RAY_INTERSECTION_BATCH_SIZE.
Extract faces directly from btConvexHullComputer (in initializePolyhedralFeatures), instead of reconstructing them, thanks to Josh Klint in #1654
PyBullet: use initializePolyhedralFeatures for convex hulls and boxes (to allow SAT)
PyBullet: expose setPhysicsEngineParameter(enableSAT=0 or 1) to enable Separating Axis Test based collision detection for convex vs convex/box and convex versus concave triangles (in a triangle mesh).