Erwin Coumans
2f3ba49357
expose some sleep timeout pybullet.setPhysicsEngineParameter(maxNumCmdPer1ms=100) or b3PhysicsParamSetMaxNumCommandsPer1ms,
...
if more commands than those are processed per millisecond, a 1ms sleep will follow, to avoid other threads being stalled.
2017-03-01 13:48:57 -08:00
Erwin Coumans
ac28f50fa5
vrhand.py first try to connect to SHARED_MEMORY if that fails use GUI fallback
2017-03-01 13:01:02 -08:00
erwincoumans
929eb49029
Merge pull request #974 from erwincoumans/master
...
expose timeout in pybullet/shared memory API
2017-02-24 15:50:26 -08:00
Erwin Coumans
a4f1e34899
expose timeout in pybullet/shared memory API
...
add RobotSimulator, a C++ API similar to pybullet. (work-in-progress, only part of API implemeted)
2017-02-24 15:34:11 -08:00
yunfeibai
2751b34894
Add maximum joint angle.
2017-02-22 14:01:03 -08:00
yunfeibai
6f2a7220a5
Modify controller constraint in the pybullet vr gripper setup.
2017-02-22 13:52:49 -08:00
Erwin Coumans
bd30ba30ce
Replace large timeout (1024*1024*1024) using real-time clock timeout (10 seconds default)
...
Change SHARED_MEMORY_MAGIC_NUMBER to make sure server/client are using the same version (shared memory)
add --realtimesimulation to physics server (GUI, VR)
remove --G Xcode from build_cmake_pybullet_double.sh
2017-02-22 09:33:30 -08:00
Erwin Coumans
218f883211
make flag/enable required argument
...
update pybullet quickstart guide PDF from
https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit#
2017-02-21 17:53:49 -08:00
Erwin Coumans
3988d363b3
Merge branch 'master' of https://github.com/erwincoumans/bullet3
2017-02-21 17:38:32 -08:00
Erwin Coumans
37890e5a4d
allow to enable/disable GUI, shadows, wireframe of OpenGL Visualizer from API
...
(pybullet.configureDebugVisualizer)
2017-02-21 17:36:54 -08:00
erwincoumans
29772fc3b4
Merge pull request #965 from jietan/pullRequest
...
Pull request
2017-02-21 05:10:01 -08:00
erwincoumans
07bd911c36
Merge pull request #966 from erwincoumans/master
...
add tiny clsocket cross-platform TCP library, update pybullet PDF doc
2017-02-20 21:17:22 -08:00
Erwin Coumans
5c74b0a199
add cmake support for TCP / clsocket in pybullet
2017-02-20 20:55:37 -08:00
Erwin Coumans
28146e816f
export TCP connection mode to pybullet
...
made TCP disconnection detection more reliable
2017-02-20 20:34:05 -08:00
Erwin Coumans
3d73a9d788
shmem preliminary TCP implementation (not working yet)
2017-02-20 16:46:25 -08:00
yunfeibai
e12981fd45
Enable logging a specified list of objects for generic robot logging.
2017-02-20 12:17:12 -08:00
yunfeibai
a3c1fec171
Add logging for generic robot and an example of logging state of kuka and cubes.
2017-02-17 17:41:57 -08:00
erwincoumans
8af62239b0
Update pybullet.c
2017-02-17 15:15:13 -08:00
Erwin Coumans
cfd35840f0
initial implementation of state logging.
...
see examples/pybullet/logMinitaur.py for example. Other state logging will include general robot states and VR controllers state.
2017-02-17 14:25:53 -08:00
Erwin Coumans
2b27ab2463
Merge branch 'master' of https://github.com/erwincoumans/bullet3
2017-02-17 10:48:03 -08:00
Erwin Coumans
34c3fca8d5
prepare state logging system (log state of robot, vr controllers after each stepSimulation)
2017-02-17 10:47:55 -08:00
Jie Tan
0665a447af
refactor to make minitaur example more general
2017-02-16 15:23:46 -08:00
Jie Tan
83e5e816f5
Merge remote-tracking branch 'bp/master' into pullRequest
2017-02-16 15:13:12 -08:00
Erwin Coumans
63486a712c
VR video recording, use command-line --mp4=videoname.mp4
...
tune gripper grasp example with tefal pan, 800Newton force.
URDF importer: if using single transform 1 child shape, don't use compound shape.
if renderGUI is false, don't intercept mouse clicks
add manyspheres.py example (performance is pretty bad, will look into it)
[pybullet] expose contactBreakingThreshold
2017-02-16 14:19:09 -08:00
Erwin Coumans
08b83c3cd8
Merge remote-tracking branch 'bp/master'
2017-02-16 13:41:12 -08:00
Jie Tan
509b77054a
now minitaur class can output joint angles, velocities and torques. I also extract evaluate functions to a file
2017-02-09 14:43:40 -08:00
Jie Tan
4df8b27626
make the motorId corresponds to that of the real minitaur. change the mass of the quadruped.urdf, change the friction of plane.urdf.
2017-02-08 17:26:36 -08:00
Erwin Coumans
0c464e6848
[pybullet] add example for roll, pitch, yaw
2017-02-08 09:27:51 -08:00
erwincoumans
46c7974927
Merge pull request #947 from erwincoumans/master
...
[pybullet] add some out-of-bounds checks, reduce run-time memory allocations
2017-02-07 12:07:40 -08:00
Erwin Coumans
56b4ac278b
pybullet workaround for very slow Mac OSX GUI mode, since OpenGL can only run in main thread, just like the Python interpreter
...
improve quadruped.py script, to allow 'useRealTime' 0 or 1
2017-02-07 08:08:55 -08:00
Jie Tan
692f7680a2
add minitaur class and test to the pull request
2017-02-06 16:27:54 -08:00
yunfeibai
be77fb269f
Add joint damping in pybullet IK example.
2017-02-03 16:36:20 -08:00
yunfeibai
df07f2aaaa
minor fix
2017-02-03 14:44:25 -08:00
yunfeibai
3442b6524a
Merge remote-tracking branch 'upstream/master'
2017-02-03 12:32:08 -08:00
yunfeibai
ac5a8aa2d6
Set joint damping in pybullet.
2017-02-03 12:03:07 -08:00
Erwin Coumans
58f37f85f4
fix type 'getMatrixFromQuaterion -> getMatrixFromQuaternion' (missing n, thanks Jie Tan for the report)
...
fix type of dimensions, visualframe in pybullet.getVisualShapeData (thanks Michael Ahn for the report)
2017-02-03 08:34:22 -08:00
erwincoumans
3a42b356e2
Add profile markers for BenchmarkDemo raytest.
...
Implement pybullet enableJointForceTorqueSensor, add forcetorquesensor.py example.
2017-01-31 10:14:00 -08:00
erwincoumans
26a34e3cda
Move ChromeTracing in its own file, and add tracing support for VR server (App_SharedMemoryPhysics_VR)
...
Add a bit of extra sleep in PhysicsServer thread, to make rendering smoother.
2017-01-29 20:59:47 -08:00
Erwin Coumans
2ea7111933
[pybullet] clear error after parsing UDP string argument (instead of shared memory 'int' argument)
2017-01-28 13:03:01 -08:00
erwincoumans
1dec1a39ce
Add the pybullet vrhand.py script used in this haptic video:
...
Make sure to run the App_SharedMemoryPhysics_VR with --norobotassets option, then
run vr_kuka_setup.py, to add some environment + objects.
2017-01-26 17:22:01 -08:00
Erwin Coumans
e652696f52
report localVisualFrame instead localInertialFrame
2017-01-25 08:29:45 -08:00
erwincoumans
d2c7d0b57d
Merge pull request #926 from erwincoumans/master
...
more improvements to pybullet (bodies/constraints are up-to-date after reconnection), pybullet quickstart guide
2017-01-22 21:22:10 -08:00
Erwin Coumans
cad45b9c20
add test script to move pr2 controller using pybullet (after initializing the world using vr_kuka_setup.py
2017-01-22 19:48:28 -08:00
Erwin Coumans
cf9f022d39
[pybullet] getNumConstraints, getConstraintInfo APIs.
...
[pybullet] updated pybullet_quickstartguide.pdf
Fail clearly (assert, return BT_INFINITY) if link index is out of range for btMultiBody methods localPosToWorld,worldPosToLocal,localDirToWorld,worldDirToLocal.
pybullet getConstraintInfo
Fix warnings due to Mac OSX 10.12 upgrade (with backward compatibility)
2017-01-22 19:08:31 -08:00
Erwin Coumans
f237c4440f
pybullet: only allow a single local in-process GUI connection
...
update pybullet quickstart guide
2017-01-21 14:30:37 -08:00
erwincoumans
d834bc72af
Merge pull request #925 from erwincoumans/master
...
Prepare for Bullet 2.86 release, update version to 2.86 (release will…
2017-01-21 12:32:41 -08:00
Erwin Coumans
64957ece9f
add hand.py/hand.ino used to create this VR glove, using MuJoCo Haptix MPL hand (Apache 2 license)
...
https://www.youtube.com/watch?v=VMJyZtHQL50
added b3InitSyncBodyInfoCommand, to retrieve body info, when connecting to a server with existing bodies
pybullet will call this b3InitSyncBodyInfoCommand automatically after connecting
Avoid overriding the py.setVRCameraState setting in VR
2017-01-20 18:13:24 -08:00
Erwin Coumans
d81d62a70b
Prepare for Bullet 2.86 release, update version to 2.86 (release will be tagged soon)
...
protect some C-API methods against negative dof indices
add triangle mesh import from MJCF files
update to recent pybullet quickstart guide pdf
2017-01-20 11:48:33 -08:00
Benelot
d3305bb76f
Change jointIndex to linkIndex in getLinkState error message.
2017-01-19 09:11:06 +01:00
Erwin Coumans
52761f5578
[pybullet] implement addUserDebugParameter / readUserDebugParameter
...
fix inertial frame for door.urdf
allow picking of links of multi-bodies with a fixed base
2017-01-17 15:42:32 -08:00
Erwin Coumans
12a391e1f9
[pybullet] expose collision filter mode and max constraint force:
...
pybullet.changeUserConstraint(maxForce=<double>)
pybullet.setPhysicsEngineParameter(collisionFilterMode=<int>)
2017-01-16 18:17:18 -08:00
Erwin Coumans
c0c4c8ba3f
fix many warnings
...
remove btMultiSapBroadphase.*
make collisionFilterGroup/collisionFilterMark int (instead of short int)
2017-01-15 22:26:11 -08:00
Erwin Coumans
9aa5a839d5
add pybullet.changeConstraint / b3InitChangeUserConstraintCommand/ b3InitChangeUserConstraintSetPivotInB /b3InitChangeUserConstraintSetFrameInB command, to change an existing user constraint.
...
add constraint.py example.
allow pybullet.createConstraint to create user constraint without a child body ('fixed' to the world)
2017-01-12 10:30:46 -08:00
Erwin Coumans
8caea20425
small tweak in inverse_kinematics.py example, to make it run better on OSX
2017-01-11 21:57:02 -08:00
Erwin Coumans
4897139dad
pybullet.calculateInverseKinematics: expose null space method with and without orientation
...
add inverse_kinematics.py and hello_pybullet.py pybullet examples
add m_worldLinkFramePosition/Orientation fields to b3LinkState, and in pybullet.getLinkState (URDF link frame in Cartesian/world coordinates)
2017-01-11 21:39:22 -08:00
Erwin Coumans
a051e6f164
fix pybullet unreachable code path
2017-01-07 10:25:10 -08:00
Erwin Coumans
4fc697f646
fix _WIN32 lacking #include <inttypes.h>
...
allow creation of multiple shared memory segments on win32.
fix pybullet compilation on Visual Studio 2010 (old compiler)
2017-01-06 10:19:19 -08:00
Erwin Coumans
83e103ac15
Add pybullet setVRCameraState and b3SetVRCameraStateCommandInit to set the VR camera root transform (position/orientation) and optional tracking object unique id (-1 for no tracking)
...
Fix robotcontrol.py script, getContactPointData -> getContactPoints
2017-01-05 17:41:58 -08:00
Erwin Coumans
c940f0ec47
update pybullet quickstart quide PDF
...
hook up the loadMJCF importing MuJoCo xml files in pybullet and shared memory API b3LoadMJCFCommandInit
2016-12-31 14:43:15 -08:00
Erwin Coumans
82995a8343
pybullet, more robust multi-server connections
...
Windows shared memory: allow to use custom key.
Improve GUI performance on Windows, submit letters in text as a batch (fewer draw-calls)
quadruped.py: first try to connect to SHARED_MEMORY, if it fails (<0) use GUI
increase Chrome about://tracing json export capacity (press 'p' in Example Browser)
UDP physics server: add --port and --sharedMemoryKey command-line arguments
PhysicsServerExample: add --sharedMemoryKey command-line option (for VR example too)
ExampleBrowser: sleep a few milliseconds if rendering is too fast, use --minUpdateTimeMicroSecs=0 to disable
2016-12-28 21:51:54 -08:00
Erwin Coumans
da2cc483b4
pybullet: allow to connect to multiple physics servers, while maintaining backwards compatibility. connect method returns an integer 'physicsClientId'. This can be passed as optional argument to each method (except for a few 'obsolete' ones.
2016-12-27 20:25:52 -08:00
Erwin Coumans
178a002cb5
prev -> prevPosition
2016-12-26 22:40:08 -08:00
Erwin Coumans
b55d76acbc
clarify field names in vrEvent.py
2016-12-26 22:36:53 -08:00
Erwin Coumans
c378d236bb
make the event fields understandable
2016-12-26 22:31:41 -08:00
Erwin Coumans
9c12e4edb0
don't reset the simulation (in C++), when pressing some VR button
...
add some little tests in vrEvent.py
2016-12-26 21:08:10 -08:00
Erwin Coumans
826c5854a8
See also pybullet quickstart guide here: https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit#
...
vrevent.py: add a Tiltbrush-style drawing example using pybullet
Expose getVREvents to pybullet / shared memory API, access to any VR controller state & state changes.
Improve performance of user debug lines (pybullet/shared memory API) by batching lines with same color/width
expose rayTest to pybullet/shared memory API (single ray for now)
add pybullet getMatrixFromQuaterion
2016-12-26 19:40:09 -08:00
Erwin Coumans
5630a63848
remove 'Kuka' postfix from pybullet.calculateInverseKinematics
...
add basic pybullet quickstart pdf documentation
2016-12-14 21:11:53 -08:00
Erwin Coumans
9ae40a59ba
export joint types in pybullet for pybullet.createConstraint
...
revert to premake4.exe, the targetsuffix etc doesn't seem to work in premake5.exe
2016-12-14 20:44:10 -08:00
erwincoumans
0c26fee04d
Merge pull request #886 from erwincoumans/master
...
some VR tweaks and bugfix for issue #878
2016-12-11 12:53:47 -08:00
Erwin Coumans
17570c4700
tweak color of quadruped robot URDF, tweak quadruped.py script to make it more compatible with VR demo
...
allow VR physics server to run with or without 'realTimeSimulation'
2016-12-11 09:28:36 -08:00
yunfeibai
9cd27b8456
Add pybullet API for changing ambient, diffuse, and specular coefficients.
2016-12-06 15:38:09 -08:00
Erwin Coumans
024ab6725b
expose pybullet.setPhysicsEngineParameter(numSubSteps=int)
2016-12-05 11:54:56 -08:00
Erwin Coumans
6814e334a2
expose numSubSteps to pybullet
2016-12-01 17:54:52 -08:00
Erwin Coumans
e20c487e52
fix backward compatibility issue with pybullet:loadURDF
2016-12-01 09:51:28 -08:00
Erwin Coumans
15cda75130
add <restitution> in <contact> settings of URDF/SDF
...
allow 'useMaximalCoordinates' and 'useFixedBase' in pybullet.loadURDF.
enable split impulse for btRigidBody, even in btMultiBodyDynamicsWorld.
allow initialization of velocity and apply force for btRigidBody in pybullet/shared memory API.
process contact parameters in URDF also for btRigidBody (friction, restitution etc)
add pybullet.setPhysicsEngineParameter with numSolverIterations, useSplitImpulse etc.
2016-11-30 22:24:20 -08:00
Erwin Coumans
32a3fb0b4d
Merge remote-tracking branch 'bp/master'
2016-11-29 19:14:04 -08:00
yunfeibai
e8ff969a6f
Merge remote-tracking branch 'upstream/master'
2016-11-29 14:17:38 -08:00
yunfeibai
0cb2b21b5f
Add pybullet API for shadow.
2016-11-29 14:10:07 -08:00
Erwin Coumans
8de35cf01c
remove prefix/postfix from pybullet, so it becomes pybullet.so and pybullet_d.so in debug mode (and on Windows, pybullet.pyd and pybullet_d.pyd)
...
fix build_cmake_pybullet_win32.bat, so it links against correct version of pythonx.lib pythonx_d.lib. Still, I would prefer using premake on Windows, it has more native Visual Studio features.
2016-11-29 09:09:35 -08:00
Erwin Coumans
2d42c7963a
add pybullet getBaseVelocity / resetBaseVelocity
...
C-API b3CreatePoseCommandSetBaseLinearVelocity/b3CreatePoseCommandSetBaseAngularVelocity
2016-11-28 15:11:34 -08:00
Erwin Coumans
2e372a525e
remove duplicate 'setTimeStep' in pybullet.c
2016-11-28 12:36:52 -08:00
erwincoumans
0516d2ecaa
allow getClosestPoints for btCompoundCollisionAlgorithm and btSphereTriangleCollisionAlgorithm
...
add optional 'lightColor' arg to testrender.py script
2016-11-22 10:11:04 -08:00
erwincoumans
0d5dcb3cc5
setDebugObjectColor
2016-11-21 07:42:11 -08:00
yunfeibai
be5b8a3d7b
Set light color in pybullet.
2016-11-20 13:14:18 -08:00
erwincoumans
9ee1c4ec24
regular OR wireframe rendering, not both
...
add option to perform filtering of 'getClosestPoints' using linkA/linkB.
don't use 'realtimesimulation' as default
add/remove debug items within same thread
pybullet, report contact points and normal as [x,y,z] triplet/vector, not 3 scalars
separate 'getClosestPointsAlgorithm': box-box doesn't report closest points with positive distance, and the query shouldn't impact regular 'closesst points'
2016-11-19 17:13:56 -08:00
erwincoumans
8c69fa13ca
add pybullet getCameraImage, replacing renderImage, cleaner API:
...
always pass in width, hight and viewMatrix, projectionMatrix, optionally lightDir
added helper methods computeViewMatrix, computeViewMatrixFromYawPitchRoll, computeProjectionMatrix, computeProjectionMatrixFOV
see Bullet/examples/pybullet/testrender.py + testrender_np.py for example use
add missing base_link.stl for husky.urdf
2016-11-17 15:15:52 -08:00
Erwin Coumans
ee7a5a470f
tweak quadruped script to make a few more moves
2016-11-16 21:36:51 -08:00
erwincoumans
2329c00faa
Add RtMidi for midi control, use the --midi option in premake, and see
...
update to OpenVR sdk 1.03 from https://github.com/ValveSoftware/openvr
add camPosX/Y/Z and camRotZ to adjust relative camera/world transform for VR (so you can align virtual table with real table etc)
tweak quadruped.py to move a bit
add mouse picking to physics server
2016-11-16 16:12:59 -08:00
Erwin Coumans
b4b93573fc
tweak quadruped.py script a little bit
2016-11-14 17:02:29 -08:00
erwin coumans
c0fb98861d
add quadruped.py script to load and initialize the a Minitaur-like quadruped
...
pybullet removeConstraint, createConstraint
rename b3CreateJoint to b3InitCreateUserConstraintCommand
add int b3GetStatusUserConstraintUniqueId(b3SharedMemoryStatusHandle statusHandle);
b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId);
2016-11-14 14:08:05 -08:00
Erwin Coumans
c521d816c6
add user debug line/text features in pybullet + shared memory API:
...
addUserDebugLine,
addUserDebugText
removeUserDebugItem
removeAllUserDebugItems
2016-11-14 07:39:34 -08:00
erwin coumans
7577c6d893
add pybullet loadBullet, saveBullet (work-in-progress) and placeholder for loadMJCF.
2016-11-11 18:07:42 -08:00
erwin coumans
b150edf76b
Merge remote-tracking branch 'bp/master'
2016-11-11 14:45:09 -08:00
erwin coumans
35fc8306fd
pybullet load/save .bullet files
2016-11-11 14:44:50 -08:00
Erwin Coumans
3b5d0f444b
various fixes
...
move btSimulationIslandManagerMt.cpp from BulletCollision to BulletDynamics
2016-11-10 16:18:20 -08:00
erwincoumans
9b5aa9a723
pybullet getOverlappingObjects added: report all object unique ids within a world space bounding box (aabb)
2016-11-10 11:22:22 -08:00
erwincoumans
6661b8d977
Merge branch 'master' of https://github.com/erwincoumans/bullet3
2016-11-09 21:01:11 -08:00
erwincoumans
0d47d61007
pybullet getClosestPoints
2016-11-09 21:01:04 -08:00
Erwin Coumans
6701947684
fix compile issues
2016-11-09 12:22:05 -08:00
erwincoumans
5d66ce20e0
network UDP: transmit structural DNA to deal with version/platform differences.
...
pybullet: allow to specify shared memory key and hostname/port for UDP.
2016-11-04 17:06:55 -07:00
Erwin Coumans
0ffd68ac32
fixes in Linux build if pybullet with enet/UDP
2016-11-04 13:36:45 -07:00
erwincoumans
e35129ceaf
Merge branch 'master' of https://github.com/erwincoumans/bullet3
2016-11-04 13:16:30 -07:00
erwincoumans
9708392322
work-in-progress
...
add UDP network connection for physics client <-> server.
also set spinning friction in rolling friction demo (otherwise objects may keep on spinning forever)
2016-11-04 13:15:10 -07:00
erwincoumans
f01389ded2
Merge pull request #842 from erwincoumans/master
...
added b3PhysicsParamSetInternalSimFlags command, and pybullet setInte…
2016-10-23 08:26:52 -07:00
erwincoumans
c2ca88bf44
added b3PhysicsParamSetInternalSimFlags command, and pybullet setInternalSimFlags API.
...
//Use at own risk: magic things may or my not happen when calling this API.
This allows to enable/disable robot assets (samurai world, gripper, KUKA robot etc) in Physics Server (and App_PhysicsServerVR etc)
1 = create robot assets
2 = create experimental box-vr-gui
Add optional command-line parameter for App_PhysicsServerVR, --norobotassets, to start with an empty world, no assets in VR (no gripper, no kuka)
2016-10-23 07:14:50 -07:00
yunfeibai
9c00b4d9f4
Add texture reset API to pybullet.
2016-10-21 17:48:06 -07:00
erwin coumans
3b8090fcc1
fix a pybullet.c issue on some compilers (don't allow for (int i=...)
...
make the build_visual_studio_vr_pybullet_double.bat smart enough to find any Python installation in c:\python*
2016-10-19 07:42:55 -07:00
erwin coumans
f97cb7002d
first version of 'getVisualShapeData' to get visual shape information to allow external renderer with pybullet and shared memory robotics API
...
b3InitRequestVisualShapeInformation/b3GetVisualShapeInformation in shared memory API
2016-10-18 22:05:28 -07:00
erwincoumans
33d9603e16
Add rudimentary 'saveWorld' command in shared memory API and pybullet, see examples/pybullet/saveWorld.py
...
Use trilinear filtering instead of bilinear
2016-10-12 23:03:36 -07:00
erwin coumans
0936ae6600
expose getNumBodies, getBodyUniqueId, getBodyInfo (char* baseName) to shared memory API and pybullet., making it easier to serialize the state of the world.
2016-09-27 12:13:45 -07:00
erwin coumans
a325747dd4
pybullet premake, keep extension
2016-09-27 08:33:53 -07:00
erwincoumans
f5e65197f4
fix pybullet.c compilation for Windows
...
add lego.urdf, duck.urdf (optimized using VHACD convex decomposition)
optimize Kiva shelf collision model (by hand, using boxes/Blender)
physics timescale toggle between 1 -> 0,25 -> 0
2016-09-24 11:25:05 -07:00
Mat Kelcey
36f7f44880
expose b3GetLinkState in pybullet
2016-09-23 15:57:35 -07:00
erwin coumans
310a330572
fix InverseKinematics+API for a case without tree (custom build Jacobian)
2016-09-22 13:27:09 -07:00
erwincoumans
ffa1e39d28
Merge pull request #797 from erwincoumans/master
...
add simple pybullet robotcontrol.py example
2016-09-21 08:14:30 -07:00
Erwin Coumans
e1ba6e9736
add simple pybullet robotcontrol.py example
2016-09-20 23:19:03 -07:00
yunfeibai
c01f6245d0
Quick fix of pybullet for IK with orientation constraint.
2016-09-20 11:10:13 -07:00
Erwin Coumans
5e09b17baf
experimental Inverse Kinematics for KUKA iiwa exposed in
...
shared memory api and pybullet. Will be extended for arbitrary bodies
and with target orientation (besides target position)
2016-09-13 23:37:46 +01:00
Erwin Coumans
7df9b69039
pybullet: add option to use NumPy to speed up, thanks to moof2k
...
option is disabled by default. When using cmake, use
cmake -DBUILD_PYBULLET=ON -DBUILD_PYBULLET_NUMPY=ON
then both testrender.py and testrender_np.py will work
without numpy only testrender.py works.
The numpy.reshape is likely a no-op when using numpy array,
so we could remove testrender_np.py...
See https://github.com/bulletphysics/bullet3/pull/774
2016-09-11 11:35:12 +01:00
Erwin Coumans
5c76b01659
allow pybullet with or without NumPy
2016-09-11 11:09:51 +01:00
Erwin Coumans
c75bbd4608
allow pybullet with or without numpy using PYBULLET_USE_NUMPY define (in build system)
2016-09-11 11:09:10 +01:00
erwin coumans
4ab02a07e5
Merge branch 'master' of https://github.com/erwincoumans/bullet3
2016-09-08 15:22:41 -07:00
erwin coumans
32eccdff61
Create project file for BussIK inverse kinematics library (premake, cmake)
...
URDF/SDF: add a flag to force concave mesh collisiofor static objects. <collision concave="yes" name="pod_collision">
VR: support teleporting using buttong, allow multiple controllers to be used, fast wireframe rendering,
Turn off warnings about deprecated C routine in btScalar.h/b3Scalar.h
Add a dummy return to stop a warning
Expose defaultContactERP in shared memory api/pybullet.
First start to expose IK in shared memory api/pybullet (not working yet)
2016-09-08 15:15:58 -07:00
Erwin Coumans
e0127bdb54
merge pybullet.c after conflicts due to Jeff's formatting pull request.
2016-09-08 11:12:58 -07:00
erwincoumans
630fcda38b
fix compile issue pybullet on MSVC 2010
2016-09-03 09:53:21 -07:00
Erwin Coumans (Google)
f7522873f9
fix compile issue on Linux
2016-09-01 22:11:07 -07:00
Erwin Coumans
e98fca1e5e
implement pybullet.getContactPointData(), two optional object unique ids as filter
...
returns a pylist of contact points. Each point has the following data:
0 int m_contactFlags;//unused for now
1 int m_bodyUniqueIdA;
2 int m_bodyUniqueIdB;
3 int m_linkIndexA;
4 int m_linkIndexB;
5-6-7 double m_positionOnAInWS[3];//contact point location on object A, in world space coordinates
8-9-10 double m_positionOnBInWS[3];//contact point location on object A, in world space coordinates
11-12-13 double m_contactNormalOnBInWS[3];//the separating contact normal, pointing from object B towards object A
14 double m_contactDistance;//negative number is penetration, positive is distance.
15 double m_normalForce;
2016-09-01 18:28:39 -07:00
erwincoumans
7790ee2f02
fix compile issue with pybullet.c on Visual Studio
2016-08-31 16:05:42 -07:00
yunfeibai
8eccac6fd8
Update CMakeLists to be the same as upstream.
2016-08-22 10:26:56 -07:00
YunfeiBai
94161246d9
Merge remote-tracking branch 'bp/master'
2016-08-19 12:02:48 -07:00
YunfeiBai
4611f5f097
Merge branch 'master' of https://github.com/YunfeiBai/bullet3
2016-08-19 12:01:09 -07:00
YunfeiBai
d26c424e11
modify cmake for pybullet
2016-08-19 12:00:55 -07:00
erwin coumans
5b0253ed47
Remove undesired assert, it makes pybullet mistakes fail in c++
...
Shared memory api/pybullet: by default, set joint motors in position PD mode with target 0, to maintain 0 joint angle.
pybullet: allow setJointControlMode(body, link, POSITION_CONTROL,targetPos etc.
2016-08-18 13:10:28 -07:00
Erwin Coumans
8f21e2bca9
fix compile issue
2016-08-17 20:01:45 -07:00
Erwin Coumans
17c16ccfa0
pybullet, deal with overflow of joints (maximum of 128 joints/links per multibody at the moment)
...
increase from 64 to 128 joints in shared memory API/pybullet
fix potential issue in tinyrenderer, related to missing segmentation mask buffer
report error if CMD_REQUEST_ACTUAL_STATE command on a multibody that exceed the number of links,
todo: stream data to allow arbitrary large number of links in shared memory API
2016-08-17 19:35:52 -07:00
erwin coumans
3bdcf23a05
Add sleep to avoid 100% busy CPU loop in PhysicsServerExample
...
Added btClock::usleep
Fix broken TinyRenderer example code.
2016-08-13 12:21:18 -07:00
Erwin Coumans
c75bebcafe
revert accidently renaming of m_depthvalues4
2016-08-12 13:55:37 -07:00
Erwin Coumans
4abe083388
fix pybullet
2016-08-11 15:58:51 -07:00
erwin coumans
a9b1544a9f
Add premake support to build pybullet, Windows and Linux tested, will enable Mac in next commit.
...
Expose inverse dynamics to Bullet shared memory API, through b3CalculateInverseDynamicsCommandInit and
b3GetStatusInverseDynamicsJointForces command/status. See PhysicsClientExeample or pybullet for usage.
Add option for Windows and Linux to set python_lib_dir and python_include_dir for premake and --enable_pybullet option
Expose inverse dynamics to pybullet: [force] = p.calculateInverseDynamics(objectIndex,[q],[qdot],[acc])
Thanks to Jeff Bingham for the suggestion.
2016-08-09 18:40:12 -07:00
Erwin Coumans
b880ddf76b
add pybullet render API with yaw/pitch/roll option
...
add testrender.py file
allow option to enable OpenGL hardware renderer in multithreaded sim
b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
2016-08-08 14:23:44 -07:00
Erwin Coumans
f5fca86d49
remove debug printf
2016-08-02 11:14:21 -07:00
Erwin Coumans
f304fd7611
add one more pybullet renderImage API and testrender.py example
...
tweak Bullet Inverse Dynamics, work-around compiler issue
2016-08-02 11:12:23 -07:00
Mat Kelcey
b4cfee8745
set dft for kd to be 1.0. note: this is only applicable to CONTROL_MODE_VELOCITY
2016-07-26 16:16:18 -07:00
Mat Kelcey
4b75c5d9d0
add another combo of args to allow kd to be configured in the CONTROL_MODE_VELOCITY case
2016-07-26 11:36:34 -07:00
Mat Kelcey
b221d2ad18
add targetPosition, targetValue, kp & kd to pybullet_setJointMotorControl
2016-07-26 11:09:12 -07:00
erwin coumans
c28cd03fbd
OpenVR controller can pick/drag objects. Instructions, Windows only:
...
Compile using premake+visual studio, and compile App_SharedMemoryPhysics_VR
Compile pybullet using cmake using cmake -DBUILD_PYBULLET=OFF -DCMAKE_BUILD_TYPE=Release ..
Create a symbolic link from c:\python\dlls\pybullet.pyd to C:\develop\bullet3\cmp\lib\Release\pybullet.dll
App_SharedMemoryPhysics_VR
Run Python. Here are some Python lines to get going:
import pybullet as p
p.connect(p.SHARED_MEMORY)
p.loadURDF("cube.urdf")
p.setGravity(0,0,-10)
p.setRealTimeSimulation(1)
Allow real-time simulation in physics server, add pybullet command setRealTimeSimulation to control it
Mesh decimation (reduce number of triangles/vertices) using a Blender modifier for Kuka IIWA and Husky
Disabled the 'glFlush' commands in GLInstancingRenderer.
Add VR controller methods to examples\CommonInterfaces\CommonExampleInterface.h
Use the ANSI version in Windows file/string operations instead of unicode, hope this doesn't break builds.
2016-07-17 23:50:11 -07:00
Mat Kelcey
588bd007e7
bug fix for pybullet_applyExternalForce where linkId wasn't actually being used in b3ApplyExternalForce call
2016-07-13 21:20:41 -07:00
Mat Kelcey
048c01d7c4
Merge branch 'master' of git://github.com/bulletphysics/bullet3 into addFovToRenderImage
2016-07-12 13:52:25 -07:00
erwin coumans
02582e3a78
shrink down cube size of BasicDemo 10 times (it looked ginormous in VR) from 2x2x2 meter to 0.2
...
add test for VR HUD/sub-titles
fix issue in previous commit, partial string use %.8s not %8.s
use long long int in b3Clock
fix warning/error in pointer alignment in serialization
Fix pybullet Windows compilation.
(thanks to bkeys/https://github.com/bulletphysics/bullet3/pull/687 )
2016-07-09 15:09:09 -07:00
Mat Kelcey
54979a0f89
pybullet renderimage with projection matrix calculated using field of view
2016-07-08 15:47:50 -07:00
Erwin Coumans
35b260b252
Merge remote-tracking branch 'bp/master'
2016-07-08 08:20:16 -07:00
erwin coumans
60d2b99151
Physics runs in a separate thread from rendering in PhysicsServerExample (preliminary)
...
Improve rendering performance. OpenVR experience is smooth now.
commit needs a bit more testing before pushing in main repo.
2016-07-07 19:24:44 -07:00
Jasmine Hsu
993bd52fe2
fix minor issues - arg parse size, spelling, duplicate function definition
2016-07-07 13:56:32 -07:00
Jasmine Hsu
43011bdb3b
merge upstream/master to latest commit ed9be25
2016-06-27 13:53:43 -07:00
Jasmine Hsu
f6bead7152
edit method definitions (docstring) for calling renderImage()
2016-06-27 13:51:28 -07:00
Jasmine Hsu
e24ec9e8c0
nearVal and farVal as params
2016-06-27 13:18:12 -07:00
Jasmine Hsu
5d5e7df7c5
exposing near/far values as params; commented out debug printf which caused failed checks
2016-06-27 11:19:57 -07:00
erwincoumans
ed9be25570
Merge pull request #669 from hellojas/loadURDF
...
fix loading urdf at default position (0,0,0)
2016-06-26 19:12:20 -07:00
Erwin Coumans
013dbda023
implement a few more pybullet methods:
...
pybullet_applyExternalForce, pybullet_applyExternalTorque, pybullet_setTimeStep,
pybullet_resetBasePositionAndOrientation,
pybullet_getQuaternionFromEuler,
pybullet_getEulerFromQuaternion
2016-06-26 18:18:30 -07:00
Jasmine Hsu
d339cf5b74
ability to call renderImage with three vectors: camera position, target position, and up vector
2016-06-24 15:30:43 -07:00
Jasmine Hsu
aa91042ac8
merge bullet master
2016-06-24 15:20:46 -07:00
Erwin Coumans
c17c39c2c9
move PD control from PhysicsServerCommandProcessor into btMultiBodyJointMotor
...
improvements/changes in pybullet API
2016-06-24 11:06:56 -07:00
Erwin Coumans (Google)
6d1948e79e
tweaks in pybullet and shared memory C-API:
...
allow to reset the state of a single joint
allow to set the target/mode for a single joint motor at a time
rename pybullet API: initializeJointPositions -> resetJointState
2016-06-24 07:31:17 -07:00
Jasmine Hsu
d2a2797201
accidently added pybullet.so
2016-06-23 14:06:14 -07:00
Jasmine Hsu
976e228be0
remove print debugger
2016-06-23 14:05:36 -07:00
Jasmine Hsu
a21889e225
remove print debugger
2016-06-23 14:01:57 -07:00
Jasmine Hsu
e0448c7613
fix loading urdf at default position (0,0,0) and adding b3 cmd to change orientation if args provided
2016-06-23 14:00:44 -07:00
Erwin Coumans
2cd0eba257
re-introduce old method in pybullet for temporary back-wards compatibility
...
b3JointControlCommandInit requires 3 args, but it was only 2,
use b3JointControlCommandInit2 for now.
2016-06-23 08:40:36 -07:00
Erwin Coumans
8b96e2de3c
a few pybullet tweaks to set desired joint motor targets (pos/vel/torque)
2016-06-22 23:21:47 -07:00
Erwin Coumans
f5ffb11bc5
fix bus error on Raspberry Pi, unaligned float access when loading STL files
...
fix pybullet Python 3 issue (PyString_FromString -> PyBytes_FromString and PyInt_FromLong -> PyLong_FromLong)
2016-06-23 05:10:00 +00:00
erwincoumans
0b249361c2
fix a c99 issue in pybullet
2016-06-21 09:01:27 -07:00
erwincoumans
01cad7c2a5
fix return type in pybullet
...
.
2016-06-20 15:00:35 -07:00
erwincoumans
b58978184c
fix C99 issue, use malloc, not variable sized array.
...
.
2016-06-20 14:58:56 -07:00
Erwin Coumans
a67df7fd03
fix cmake and premake build systems, after adding texture support in SDF,
...
in a nutshell, add the following two files:
examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
examples/ThirdPartyLibs/stb_image/stb_image.cpp
2016-06-19 17:35:25 -07:00
Erwin Coumans
53a0772257
fix some issues related to controlling a robot/multibody beyond body index 0
...
(most testing happened with a single robot/multibody so far)
preliminary pybullet.setJointControl implementation
2016-06-16 18:46:34 -07:00
Jasmine Hsu
03fded3dc7
getJointPositions returns a list of all joint positions for a given bodyIndex
2016-06-15 14:21:04 -07:00
Jasmine Hsu
934725554f
remove initializeJointPosition as setting one joint is not supported
2016-06-14 15:21:50 -07:00
Jasmine Hsu
d6ab1ab434
initialize a single joint position for a given body index
2016-06-14 14:58:36 -07:00
Jasmine Hsu
d53d6366de
get the state of a specific joint given a body index
2016-06-14 14:35:45 -07:00
Jasmine Hsu
55560e114e
merge bulletphysics:master to commit:b06e1cb
2016-06-14 14:13:54 -07:00
Jasmine Hsu
eeaff0747b
return joint state given a joint index and body index
2016-06-14 14:08:24 -07:00
erwincoumans
6523df336e
Fix pybullet Windows build errors: C99 requires variables to be defined at the start of the function.
...
Improve CMake Windows support to build PyBullet (BUILD_PYBULLET)
Implement b3LoadSdfCommandInit in shared memory API
Implement pybullet SDF loading binding, in loadSDF API
TODO for SDF support is provide way to query object/link/joint information.
2016-06-13 10:11:28 -07:00
Jasmine Hsu
9c5a7925f0
add internal set matrix function
2016-06-10 15:14:00 -07:00
Jasmine Hsu
b0c7c086e3
render image with ability to set pixel resolution and initial camera position
2016-06-10 15:07:41 -07:00
Erwin Coumans
98d2f91f3c
fix flipped tinyrenderer image
2016-06-09 12:12:46 -07:00
Erwin Coumans
d2e50d045b
fix issues related to camera width/height
...
add width,height as arguments to pybullet.renderImage(x,y,[viewMat4x4],[projMat4x4])
2016-06-07 16:11:58 -07:00
Erwin Coumans
1c7f87aff1
implement first draft of pybullet.renderImage for synthetic camera
...
remove a few debug printf from tinyrenderer
2016-06-06 18:54:05 -07:00
erwin coumans
68545fb71a
fix pybullet.getPositionAndOrientation crash/issues
2016-05-26 15:58:10 -07:00
Erwin Coumans
535ee33e3b
fix build3/stringify.sh
...
fix some compile issues
2016-05-25 15:37:28 -07:00
Erwin Coumans
bd1620eda8
add pybullet.getBasePositionAndOrientation
...
add missing file to pybullet CMakeLists.txt
2016-05-24 15:29:26 -07:00
Erwin Coumans
cdd6954ada
fix pybullet cmake compilation
2016-05-18 15:07:42 -07:00
erwincoumans
119d47166d
Update test.py
2016-05-10 01:28:45 -07:00
erwincoumans
15ce069c04
Update test.py
2016-05-10 01:26:13 -07:00
erwincoumans
9ba3a844c0
Update test.py
2016-05-10 01:24:40 -07:00
erwincoumans
94fe96e2b4
Update test.py
2016-05-10 01:13:19 -07:00
erwin coumans
99073e03f7
Allow to compile pybullet on Windows, using CMake
...
(got it to run, rename pybullet.dll into pybullet.pyd and copy in c:\python34\dlls)
Update test.py
Allow to compile pybullet using Python 3.x and 2.7
2016-05-10 00:57:54 -07:00
Erwin Coumans
b0a4e126bf
use cmake FIND_PACKAGE(PythonLibs 2.7 REQUIRED) if pybullet is build
2016-05-04 13:24:06 -07:00
Erwin Coumans
938db633df
fixes in build system
2016-05-03 23:34:48 -07:00
Erwin Coumans
709a55d5ab
add CMake support for pybullet (still preliminary)
...
requires shared library build:
cmake .. -DBUILD_SHARED_LIBS=on
then create a symbolic link from libpybullet.so to pybullet.so
2016-05-03 13:03:12 -07:00
Erwin Coumans
fb65c29033
use "world" to make door static (instead of using mass = 0)
...
minor improvements to pybullet
2016-05-03 12:59:21 -07:00
Erwin Coumans
1d0f038aad
add initial pybullet module, using the shared memory API
...
(for now, start the example browser in 'physics server',
then compile using premake --python option,
then run python in the bin folder (so it finds pybullet.so)
and run the test.py script in examples/pybullet folder.
The robotics shared memory C API is very suitable for this.
2016-04-30 11:18:54 -07:00