Page 1 of 1
sim.getContactInfo when object connected to another one
Posted: 03 Jan 2024, 04:53
by CroCr
I did attach capsule to the end-effector of kuka youBot robot. I did attach it to "Rectangle 7" in the model via a force sensor. When I try to get the contact info (i.e. specifically force data), I'm getting zero force even though the capsule hits a wall. I did shift the capsule a bit so there is no physical contact with the model without removing the force sensor and it works. My question is why when the capsule physically overlaps with the gripper no contact info reported?
Re: sim.getContactInfo when object connected to another one
Posted: 03 Jan 2024, 06:47
by coppelia
Hello,
the capsule should not overlap with the gripper model, otherwise some internal forces should be generated. Not sure exactly how your set-up looks like, but if you can post a link to your scenes (each corresponding to what you describe), then we can check what is going on.
Cheers
Re: sim.getContactInfo when object connected to another one
Posted: 03 Jan 2024, 07:36
by CroCr
coppelia wrote: ↑03 Jan 2024, 06:47
Hello,
the capsule should not overlap with the gripper model, otherwise some internal forces should be generated. Not sure exactly how your set-up looks like, but if you can post a link to your scenes (each corresponding to what you describe), then we can check what is going on.
Cheers
In the case the capsule not overlapped with the gripper, how I can avoid the capsule from tilting when interacting with a wall? When strong force is applied on the capsule, the entire platform needs to move, not just the capsule.
Re: sim.getContactInfo when object connected to another one
Posted: 04 Jan 2024, 16:55
by coppelia
To read the force/torque applied to the force/torque sensor, use sim.readForceSensor.
If you want to use sim.getContactInfo, then make sure to correctly use it, e.g.:
Code: Select all
function sysCall_sensing()
local index = 0
while true do
collidingObjects, collisionPoint, reactionForce, normalVector=sim.getContactInfo(0, CapsuleHandle, index)
if next(collidingObjects) then
print("Collision between " .. sim.getObjectAlias(collidingObjects[1]) .. " and " .. sim.getObjectAlias(collidingObjects[2]))
print("Reaction force is " .. getAsString(reactionForce))
index = index + 1
else
break
end
end
end
Cheers
Re: sim.getContactInfo when object connected to another one
Posted: 05 Jan 2024, 01:16
by CroCr
coppelia wrote: ↑04 Jan 2024, 16:55
To read the force/torque applied to the force/torque sensor, use sim.readForceSensor.
If you want to use sim.getContactInfo, then make sure to correctly use it, e.g.:
Code: Select all
function sysCall_sensing()
local index = 0
while true do
collidingObjects, collisionPoint, reactionForce, normalVector=sim.getContactInfo(0, CapsuleHandle, index)
if next(collidingObjects) then
print("Collision between " .. sim.getObjectAlias(collidingObjects[1]) .. " and " .. sim.getObjectAlias(collidingObjects[2]))
print("Reaction force is " .. getAsString(reactionForce))
index = index + 1
else
break
end
end
end
Cheers
Thank you so much. I'm only interested in the collision between capsule and the wall. How can I can modify your Lua script for this purpose? From your script, it appears I need to go through list of objects for getContactInfo in the scene.
Specifically, I need one function to get the contact info. The actual function I was using this
Code: Select all
function getReactionForces()
local forces = {}
collidingObjects, collisionPoint, reactionForce, normalVector=sim.getContactInfo(0, CapsuleHandle, sim.handleflag_extended)
if collidingObjects then
forces[1] = reactionForce[1]
forces[2] = reactionForce[2]
forces[3] = reactionForce[3]
end
return forces
end
This code works fine if the capsule doesn't overlap with the gripper. However, since there is an overlapping, I'm not sure how can I handle it. From your answer, it seems I need to go through list of objects each time I can getReactionForce(). Is this right? This is what I've done
Code: Select all
function getReactionForces()
local forces = {}
local index = 0
while true do
collidingObjects, collisionPoint, reactionForce, normalVector = sim.getContactInfo(0, CapsuleHandle, index)
if next(collidingObjects) then
if sim.getObjectAlias(collidingObjects[2]) == 'Wall' then
forces[1] = reactionForce[1];
forces[2] = reactionForce[2];
forces[3] = reactionForce[3];
break
end
index = index + 1
else
break
end
end
return forces
end
I get this error
Code: Select all
[/youBot@childScript:error] [string "/youBot@childScript"]:81: bad argument #1 to 'next' (table expected, got nil)
stack traceback:
[C]: in function 'next'
[string "/youBot@childScript"]:81: in function 'getReactionForces'
Re: sim.getContactInfo when object connected to another one
Posted: 05 Jan 2024, 07:39
by coppelia
Yes, you need to filter the information returned if you only need to contact information between the stick and the wall. Or of course you could just read the force sensor forces (which would not be exactly the same though).
When using your code, I do not get any error with next(collidingObjects)... make sure ou are running with the latest CoppeliaSim (V4.6, you are running with V4.5)
Cheers
Re: sim.getContactInfo when object connected to another one
Posted: 05 Jan 2024, 21:39
by CroCr
coppelia wrote: ↑05 Jan 2024, 07:39
Yes, you need to filter the information returned if you only need to contact information between the stick and the wall. Or of course you could just read the force sensor forces (which would not be exactly the same though).
When using your code, I do not get any error with next(collidingObjects)... make sure ou are running with the latest CoppeliaSim (V4.6, you are running with V4.5)
Cheers
I had to remove next() to make it to work in V4.5. If you don't mind, I have two questions. In which frame forces are measured in case using getContactInfo() and using force sensor?
Re: sim.getContactInfo when object connected to another one
Posted: 08 Jan 2024, 09:07
by coppelia
This depends on when you call sim.getContactInfo or sim.readForceSensor. Have a look at the
main script: every force/torque measurement happens when calling sim.handleDynamics. This is called at the end of the actuation section. This means that you should always call sim.getContactInfo or sim.readForceSensor from within the sensing section, in order to read the forces/torques applied in current frame. Otherwise you'll read the forces/torques from previous frame.
Keep also in mind that sim.readForceSensor will read the average forces/torques when more than one dynamic simulation steps are executed when calling sim.handleDynamics (by default, sim.handleDynamics will execute 10 individual dyn. simulation steps)
Cheers