Search found 4184 matches

by Erwin Coumans
Thu Oct 24, 2019 1:58 am
Forum: PyBullet Support and Feedback
Topic: What's the best way to pin a rigid body to another rigid body?
Replies: 1
Views: 513

Re: What's the best way to pin a rigid body to another rigid body?

The best way is to create a new URDF and attach them as a fixed joint. You can use the URDF editor to do this. See this example how to combine a car and a kuka: https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/gym/pybullet_utils/examples/combineUrdf.py Alternatively, you get so...
by Erwin Coumans
Thu Oct 24, 2019 1:56 am
Forum: PyBullet Support and Feedback
Topic: How to convert rotation matrix to quaternion in PyBullet
Replies: 2
Views: 501

Re: How to convert rotation matrix to quaternion in PyBullet

Only Euler <-> Quaternion conversions are exposed in PyBullet, not the Matrix <-> Quaternion yet.
by Erwin Coumans
Thu Oct 24, 2019 1:55 am
Forum: PyBullet Support and Feedback
Topic: Segment-wise collision detection
Replies: 1
Views: 230

Re: Segment-wise collision detection

You could use getClosestPoints to get a better conservative answer how far you can safely move, and then use bigger steps along your trajectory.
by Erwin Coumans
Thu Oct 24, 2019 1:53 am
Forum: PyBullet Support and Feedback
Topic: The difference between setJointMotorControl2 and resetJointState
Replies: 1
Views: 180

Re: The difference between setJointMotorControl2 and resetJointState

reset* functions teleport the robot into some state, ignoring all dynamics. setJointMotorControl2 will set some targets and let the simulation try to achieve those, so they obey the laws of physics. The examples may use one or the other. It is best to never use reset* functions while simulating, onl...
by Erwin Coumans
Thu Sep 05, 2019 2:35 pm
Forum: PyBullet Support and Feedback
Topic: Dynamically attached fixed joint is not fix
Replies: 1
Views: 445

Re: Dynamically attached fixed joint is not fix

Mouse forces are very strong and possibly stronger than the fixed joint constraint forces. It is better to attach a fixed joint as part of the urdf instead of using a constraint.
by Erwin Coumans
Thu Sep 05, 2019 2:34 pm
Forum: General Bullet Physics Support and Feedback
Topic: Chain of constraints is very unstable if masses differ
Replies: 2
Views: 419

Re: Chain of constraints is very unstable if masses differ

You can use btMultiBody instead, together with some velocity motors to model joint friction/damping. It is easiest to prototype this directly in PyBullet first, see its quickstart guide . For btRigidBody, using a smaller time step would help more than increasing the number of iterations, but btMulti...
by Erwin Coumans
Sat Aug 24, 2019 12:26 am
Forum: PyBullet Support and Feedback
Topic: Connecting pybullet to a C++ Bullet Physics instance?
Replies: 1
Views: 363

Re: Connecting pybullet to a C++ Bullet Physics instance?

Yes, you can create a PyBullet server and client and also connect to this from a C++ client using the C-API, which is pretty much identical to the PyBullet API (PyBullet uses this same C API). The API header file is here: https://github.com/bulletphysics/bullet3/blob/master/examples/SharedMemory/Phy...
by Erwin Coumans
Sat Aug 24, 2019 12:23 am
Forum: General Bullet Physics Support and Feedback
Topic: Create bullet shape from .obj mesh
Replies: 5
Views: 4074

Re: Create bullet shape from .obj mesh

PyBullet has some examples that create a mesh (convex or concave) from an .obj file or from vertices in memory. See https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/examples/createMesh.py https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/examples/createText...
by Erwin Coumans
Sat Aug 24, 2019 12:21 am
Forum: General Bullet Physics Support and Feedback
Topic: Pybullet Deterministic Simulation
Replies: 2
Views: 563

Re: Pybullet Deterministic Simulation

PyBullet is fully 100% deterministic after calling resetSimulation and adding the objects in the same order. Many of our reinforcement learning environments rely on this. In fact, there are unit tests that show that PyBullet is also fully deterministic after a save/restoreState call, not just resetS...
by Erwin Coumans
Wed Aug 07, 2019 8:11 pm
Forum: General Bullet Physics Support and Feedback
Topic: Bullet on colab
Replies: 2
Views: 540

Re: Bullet on colab

OpenGL isn't available from within a colab/browser. You can still use getCameraImage to render images, using the software renderer. (TinyRenderer)
by Erwin Coumans
Tue Jun 25, 2019 8:43 am
Forum: General Bullet Physics Support and Feedback
Topic: Tossing Bot simulation environment
Replies: 1
Views: 481

Re: Tossing Bot simulation environment

I don't think this environment is made open source.
by Erwin Coumans
Thu May 02, 2019 4:28 pm
Forum: General Bullet Physics Support and Feedback
Topic: Stabilize "dantzing" on nearby contacts using custom combiner callback.
Replies: 4
Views: 663

Re: Stabilize "dantzing" on nearby contacts using custom combiner callback.

For robotics purposes we developed the btMultiBody and PyBullet and its C and C++ robotics API . You may want to try btMultiBody instead of btRigidBody, and PyBullet/C++ robotics API has most of the settings more suitable for such tasks. So I suggest to create a quick prototype in PyBullet and then ...
by Erwin Coumans
Fri Apr 12, 2019 1:38 am
Forum: General Bullet Physics Support and Feedback
Topic: Load File from URDF and convert to Rigidbody (RobotSimulator)
Replies: 2
Views: 790

Re: Load File from URDF and convert to Rigidbody (RobotSimulator)

There is a better way to limit motion for reduced coordinate (btMultiBody): instead of using a free base, use a fixed base and add additional degrees of freedom to enable motion along the axis you want. See the biped2d example how this is done: https://github.com/bulletphysics/bullet3/blob/master/ex...
by Erwin Coumans
Fri Apr 12, 2019 1:33 am
Forum: PyBullet Support and Feedback
Topic: Manipulating Kuka-robot joint using Torque-control
Replies: 2
Views: 1141

Re: Manipulating Kuka-robot joint using Torque-control

You need to first unlock/disable the default velocity/position motor: pybullet.setJointMotorControl2(objUid, linkIndex, p.VELOCITY_CONTROL, force=0) Otherwise, your force/torque has to exceed the default motor. Instead of using 0, you can also use a very small force limit, to mimic joint friction. I...
by Erwin Coumans
Tue Apr 09, 2019 6:13 am
Forum: General Bullet Physics Support and Feedback
Topic: why call the computeAccelerationsArticulatedBodyAlgorithmMultiDoft twice?
Replies: 2
Views: 478

Re: why call the computeAccelerationsArticulatedBodyAlgorithmMultiDoft twice?

Good point, the second pass is used for joint feedback (using results from the constraint solver).

We can add a check for 'body->internalNeedsJointFeedback()' around line 720 of btMultiBodyDynamicsWorld. Mind sending a patch to github?