[ODE] can"t get friction to lift an object with a robot arm
Jon Watte (ODE)
hplus-ode at mindcontrol.org
Sun Sep 2 18:46:27 MST 2007
Among the contact joint flags, there is one that turns on contact mu --
if that flag is not set, the friction model is just a force limit, and
"mu" is actually a force value.
Other than that, I don't know what could be wrong from your description.
It may be that the constraint system looks at the mass and velocity of
the attached bodies, and if there is no body for the geom, it can't
account for the velocity of the geom. Add a heavy body, as an
experiment, and set the velocity appropriately.
"Grabbing" in general is kind of hard, though, as it often involves
subtle deformations that aren't modeled in a typical rigid body system.
Cheers,
/ h+
Peter Pastor wrote:
> Hey,
>
> thanks for the quick response...
>
> so, what do you mean by "better" friction model ?! I tried a lot of
> combinations of various parameters... and I think with...
>> contact[i].surface.mu = dInfinity;
> ... I have a sufficiently high "mu". Don't you think ?! Could you give an
> example configuration... that would help a lot !
>
> So, I may not have made clear that the dCappedCylinder I "put" around the
> fingers of the robot arm are only dGeoms. there is no body attached to them.
> The reason for that is that I want them to be static. So, what is the best
> way in order to get friction... it is really strange that once in a while,
> after the grasping, the robot is holding the object, so that the object does
> not fall down. but as soon as the gripper is moving... the friction
> disappears. (see video)
>
> http://manet.usc.edu/~pastor/miss_placing.avi
>
> thank you for any help,
> peter
>
> On Sunday 02 September 2007 12:03:07 you wrote:
>> You need to turn on the better friction model, and set a sufficiently
>> high "mu".
>>
>> Btw: you're not supposed to move the geoms themselves; you're supposed
>> to move the body (typically through applying forces), and the geom will
>> follow.
>>
>> Cheers,
>>
>> / h+
>>
>> pastor wrote:
>>> hey there,
>>>
>>> I am currently working on making a robot arm grasp an object and place it
>>> somewhere. I calculate the arm configuration externally and in order to
>>> get some interaction between the robot and the boxes (modeled as bodies)
>>> I set some geoms (dCappedCylinder) around the fingers and update their
>>> position and orientation according to the current robot configuration.
>>> During grasping everything seems to work.. the finger collide with the
>>> object an pushes it into the right directions... after closing the
>>> gripper the collision remains but I cannot lift this stupid box. I played
>>> with all the parameters... what am I doing wrong ? Waht needs to be done
>>> to the amount of force which allows me to lift an objet... the pase some
>>> code (which shows the current set of parameters... I had a lot of
>>> different setttings...) so that you have some idea what I really do... I
>>> hope this helps. I also include a little movie which shows this
>>> behaviour...
>>>
>>> http://manet.usc.edu/~pastor/miss_placing.avi miss_placing.avi
>>>
>>> hope you understand my problem...
>>>
>>> I really need some advice ! so... thanks for any help
>>>
>>> peter.pastor at gmail.com
>>>
>>> ---------------------------- code
>>> --------------------------------------------------------------
>>> static void nearCallback (void *data, dGeomID o1, dGeomID o2) {
>>> dBodyID b1 = dGeomGetBody(o1);
>>> dBodyID b2 = dGeomGetBody(o2);
>>>
>>> dContact contact[MAX_CONTACTS];
>>>
>>> int i;
>>> for(i=0; i<MAX_CONTACTS; i++)
>>> {
>>> /* contact[i].fdir1[0] = 0.3; */
>>> /* contact[i].fdir1[1] = 0.3; */
>>> /* contact[i].fdir1[2] = 1.0; */
>>> /* normalize3DArray(contact[i].fdir1); */
>>> /* // contact[i].fdir1[3] = 0; */
>>> contact[i].surface.mode = /* dContactMotion1 | *//*
>>> dContactApprox1 | */ dContactSoftERP /*| dContactSlip1 | dContactSlip2 */
>>> /* |dContactFDir1 */
>>>
>>> |/* dContactBounce | */ dContactSoftCFM | dContactMu2;
>>>
>>> contact[i].surface.mu = dInfinity;
>>> //contact[i].surface.mu = 1;
>>> contact[i].surface.mu2 = dInfinity;
>>> // contact[i].surface.bounce = 0.005;
>>> // contact[i].surface.bounce = 0;
>>> // contact[i].surface.bounce_vel = 0.8;
>>> // contact[i].surface.soft_cfm = 1e-04;
>>> contact[i].surface.soft_cfm = 1e-05;
>>> contact[i].surface.soft_erp = 2;
>>> }
>>>
>>> int numc = dCollide(o1, o2, MAX_CONTACTS, &contact[0].geom,
>>> sizeof(dContact));
>>> if(numc) {
>>> for(i=0; i<numc; i++) {
>>> dJointID c = dJointCreateContact(World, contactgroup, contact + i);
>>> dJointAttach(c, b1, b2);
>>> }
>>> }
>>> }
>
>
>
>
More information about the ODE
mailing list