Spherical Joints

Official Python bindings with a focus on reinforcement learning and robotics.
Post Reply
MIT
Posts: 12
Joined: Fri Nov 03, 2017 8:21 pm

Spherical Joints

Post by MIT »

Now that pybullet supports spherical joints, I have some questions around their usage:

1) getJointState() still returns a single float for the spherical joint jointPosition field. Shouldn't this be a quaternion? Is there another method I should be calling to get the state of a spherical joint?

2) setJointMotorControlMultiDof() now accepts the force parameter as a sequence of 3 floats. However inside the example file:

https://github.com/bulletphysics/bullet ... able_pd.py

this is passed in as force=[jointFrictionForce,jointFrictionForce,jointFrictionForce] . Is this still a max force when using position control and the example just misnamed as friction force?


Thanks for the help!
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA
Contact:

Re: Spherical Joints

Post by Erwin Coumans »

Spherical joints still need a bit more work indeed.

I'll add the getJointStateMultiDof for spherical joints soon.

setJointMotorControlMultiDof indeed sets the maxForce. It is not misnamed: if you set a target velocity of 0, the joint motor can model joint friction given the maximum (friction) force. Of course you can also use setJointMotorControlMultiDof to model a joint motor actuator instead.
MIT
Posts: 12
Joined: Fri Nov 03, 2017 8:21 pm

Re: Spherical Joints

Post by MIT »

Erwin,

Thanks for the information and work on the spherical joints. Using setJointMotorControlMultiDof to model joint friction is very interesting and apologies for presuming it was a mistake. Looking forward to being able to switch to spherical joints inside my project.
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA
Contact:

Re: Spherical Joints

Post by Erwin Coumans »

This PR exposes the torques: https://github.com/bulletphysics/bullet3/pull/2130

Thanks for the report!

By the way, the DeepMimic humanoid can be trained using stable PD control now:
https://www.youtube.com/watch?v=aiWxIjtMMFI

When switching to spherical joint motors, the policy doesn't train. See the switch here, _useStablePD:
https://github.com/bulletphysics/bullet ... nv.py#L274
I haven't looked into why not.
MIT
Posts: 12
Joined: Fri Nov 03, 2017 8:21 pm

Re: Spherical Joints

Post by MIT »

Awesome, giving spherical joint motors a try now (note: I'm not using the DeepMimic code). I'll let you know if it works to give you another data point to debug with (and likely be joining in the debugging efforts if it doesn't work ;).
MIT
Posts: 12
Joined: Fri Nov 03, 2017 8:21 pm

Re: Spherical Joints

Post by MIT »

Erwin,

I'm seeing two different sets of weird behavior with spherical joints that might partly explain why joint motor control with them isn't working for you (or I might just be doing something dumb).

In order to help demonstrate what's going on, I created the attached example.py. It loads your humandoid.urdf and allows for testing of joints via sliders. Note that it converts spherical joints into (yaw, pitch, roll) for manipulating the slider values. The forum won't let me upload files with urdf/py extensions so I added a .txt extension to the files, just remove it and they should both work. I'm also attaching the humanoid.urdf for convenience.

There are two odd things happening that they demonstrate:

1) p.resetJointStateMultiDof() seems to reset to the default position after being called. In order to see this, open up example.py and uncomment line #101:

p.resetJointStateMultiDof( model, joint_names_to_id['right_shoulder'], eulerToQuaternion(-math.pi/2, 0, 0) )

and comment out line #118:

#applyAction( model, ordered_joint_indices, commands )

When you run the example, notice how the right arm returns to it's default position immediately after loading. Now, comment out line #101 and uncomment line #102.

p.resetJointState( model, joint_names_to_id['right_elbow'], math.pi/2 )

We don't see the same behavior for resetJointState().

2) Comment out line #101 and #102, and uncomment line #118 (applyAction). Now drag around any of the pitch or roll sliders. Notice that no matter how fast you drag them things are stable. Now slowly drag a yaw slider, and then drag it around quickly. Notice that when you drag it quickly the joint rotates off access.

My guess for #2 is that the underlying quaternion library bullet is using is switching over to the opposite direction rotation quaternion and this is causing the joint go off axis. If you add a

print( target_position )

at line #53 you can see the quaternions that are being passed in to p.setJointMotorControlMultiDof(). The quaternions being passed in appear to be smooth (ie I get the same value if I drag the slider slowly to the far right as if I drag it quickly), but maybe there is something wrong with my usage of the api?


Edited to add:

I'm working off trunk as of yesterday afternoon to make sure we're both using the same code.
Attachments
example.py.txt
(3.85 KiB) Downloaded 749 times
humanoid.urdf.txt
(9.6 KiB) Downloaded 759 times
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA
Contact:

Re: Spherical Joints

Post by Erwin Coumans »

The humanoidMotionCapture.py example shows how to use spherical drives. Also one of the humanoids in that example use resetJointStateMultiDof to set its state. Both modes works just fine with me. Please check it.
MIT
Posts: 12
Joined: Fri Nov 03, 2017 8:21 pm

Re: Spherical Joints

Post by MIT »

Spherical joints themselves work fine for me, and the file you linked is the example I figured out the API from. My issue is with the behavior I'm seeing of p.resetJointStateMultiDof(). Did you happen to run the example I provided? If not, I've attached an even simpler version to this reply. All it does is load the humanoid model and call resetJointStateMultiDof() on one of the spherical joints. There are no other calls made to change the joint state. And yet while the joint does move to the position specified in p.resetJointStateMultiDof(), it immediately moves back to its default position after the call is made. This is different then the behavior of resetJointState(), which leaves the joint at the position that it is set to in the reset call. Could you kindly run the example script and point out what I am doing wrong with the call to p.resetJointStateMultiDof vs the call to resetJointState()?
Attachments
simple.py.txt
(2.33 KiB) Downloaded 716 times
humanoid.urdf.txt
(9.6 KiB) Downloaded 755 times
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA
Contact:

Re: Spherical Joints

Post by Erwin Coumans »

You didn't disable the motors, as is done in humanoidMotioncapture.py, add this block:

Code: Select all


#disable motors
for     j       in range (p.getNumJoints(model)):
        ji = p.getJointInfo(model,j)
        targetPosition=[0]
        jointType       =       ji[2]
        if (jointType   == p.JOINT_SPHERICAL):
                targetPosition=[0,0,0,1]
                p.setJointMotorControlMultiDof(model,j,p.POSITION_CONTROL,targetPosition, targetVelocity=[0,0,0], positionGain=0,velocityGain=1,force=[0,0,0])
        if (jointType==p.JOINT_PRISMATIC or     jointType==p.JOINT_REVOLUTE):
                p.setJointMotorControl2(model,j,p.VELOCITY_CONTROL,targetVelocity=0, force=0)



MIT
Posts: 12
Joined: Fri Nov 03, 2017 8:21 pm

Re: Spherical Joints

Post by MIT »

Doh, in the end it was in fact something stupid on my part. My reading comprehension is indeed in need of some work, sorry for asking you to debug stuff for me. To be fair though even in the example you provided disabling the joints is below the reset call, so any easy mistake to make if you're not paying attention (and the comment mentioning disabling was suspiciously absent from the version of the file I was reading ;) ). It does beg the question why I don't see the same behavior with setJointMotorControl2(), but honestly that's a question for another time.

Ok, as I mentioned previously spherical joint motors are fully functional for me. Thus on the topic of the DeepMimic not working with spherical joint motors, it's very likely something to do with the DeepMimic code vs the spherical joint implementation. If it were me, a few places I would look are:

a) The default inertial moments of 0.1 used in the humandoid.urdf are very large for an actual human. It might be worth lowering these values, for instance an arm is much more in the 0.008 range. Edit: I glanced at the DeepMimic URDF and assuming the BodyDef's param's define the inertial moments, 0.1 is more inline with the scale DeepMimic is using. That said the DM URDF does appear to use values based on the shape of links/joints, not sure how big of a impact this would have vs just using 0.1 for everything where you are essentially using cubes.

b) DeepMimic was originally designed to run at a step frequency of 1200 in order for friction to work properly. Apologies if you are already aware of this, but I thought it might be worth pointing out in case you were running at a lower frequency.

c) Again I haven't had the chance to go thru your implementation of DeepMimic so apologies if you already know this, but parallelization definitely matters here. I believe DeepMimic was originally trained across 16 cores, so I would make sure you have a similar setup.

Unfortunately I don't have time to dig into your implementation and help out more until mid April, but if it's still not working by then I'll try and get it running on my end.
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA
Contact:

Re: Spherical Joints

Post by Erwin Coumans »

Actually my implementation of DeepMimic in PyBullet is working fine. We ignore the inertia data from URDF and recompute it based on collision shapes, and that data is identical from the original DM. We can re-use the original policy with stable PD control, so all is fine.

You can use 1200Hz, but by default I use 120Hz in PyBullet and it still works very fine. Also, I re-use the identical training framework of Jason Peng, so it is multi-threaded.

The only thing that doesn't work yet is using spherical joints, instead of stable PD controllers.
Post Reply