Torque control

Typically: "How do I... ", "How can I... " questions
Husnu

Re: Torque control

Post by Husnu »

Thank you very much!

dds
Posts: 76
Joined: 20 Mar 2014, 14:35

Re: Torque control

Post by dds »

Hello. I have a question about it. I tried the following code in the Pioneer model:

Code: Select all

simSetJointTargetVelocity(motorLeft,9999)
simSetJointTargetVelocity(motorRight,9999)

simSetJointForce(motorLeft,0.01)
simSetJointForce(motorRight,0.01)
I assumed that the robot should move in a straight line, but does not.It moves sideways and even backwards.
I tried with different physical engines, each one produce a different effect.
With ODE the robot stays in a straight line when very small torques are applied. However after a few seconds deviates or braking.

coppelia
Site Admin
Posts: 7838
Joined: 14 Dec 2012, 00:25

Re: Torque control

Post by coppelia »

Hello,

you are right, there are several things that come together here:
  • The caster in the back is causing problems at certain speeds/torques. You can improve the results by reducing its mass and inertia. But the best would be to reduce the thickness of the caster wheel (e.g. divide it by 4). Another possibility is to give the caster a friction of 0, but in that case it will not look and behave very realistically
  • You should always remember that a joint with a very small force/torque will almost behave as a free and frictionless joint. On a flat ground, a vehicle with such wheels can behave in a strange way (this also depends on the physics engine). If you want your wheels (or motors) to stand relatively still (or act as a high-friction joint), set a velocity of zero, and a high torque.
  • Very high velocities can also result in strange behaviours
Cheers

dds
Posts: 76
Joined: 20 Mar 2014, 14:35

Re: Torque control

Post by dds »

Hi! I tried all these options but still doesn't get the desired behavior. ¿how does physics engine calculates the force / velocity relation?

coppelia
Site Admin
Posts: 7838
Joined: 14 Dec 2012, 00:25

Re: Torque control

Post by coppelia »

When testing, always look below the Pioneer robot, and check what the caster wheel is doing: the strange movement that might happen at the beginning is related to the caster wheel. Of course if you use relatively extreme values, it will become unstable.

This is a corrected version of the Pioneer, that will be in next release (V3.1.2).

Cheers

erik
Posts: 5
Joined: 03 Dec 2014, 15:54

Re: Torque control

Post by erik »

Hi all,

Currently, I'm making a simulation of a torque controlled humanoid. I tried the method explained above (i.e.: set the target velocity to a large number and in each loop, adjust the maximum torque), but it did not work. I did find another way that seems to work.

My test case is as follows: for a simple robot (e.g. a 2dof arm), I want to calculate the gravity component in joint space and use those torques as control inputs on the joints directly to compensate gravity. I looked in the ODE source, where you can do this via the function dJointAddHingeTorque, which sets opposite body torques on the connected bodies (see: http://robotics.naist.jp/~akihiko-y/dox ... tml#l00318). So I reproduced this in v-rep using the function simAddForceAndTorque. This almost gave me gravity compensation, but it became unstable quite quickly. I suspect because the dynamics are not calculated in joint space, causing numeric errors. So I needed some damping. I added that by enambling the motors for the joints, setting the reference velocity to 0 and a very low maximum torque. Because the errors are numeric, a maximum of 0.000001 sufficed. I hope this solution will work for others as well!

I do have two more questions related to this:
1. In future releases, will directly setting joint torques be possible? Either by supporting dynamics in joint space (such as the newer Bullet versions) or by making an API / GUI for ODE functions like dJointAddHingeTorque? For many control techniques, this would be very useful!
2. I want to compute my control algorithms in Matlab, but I did not find a function similar to simAddForceAndTorque where I can set body torques. How can I set body forces and body torques via Matlab?

Erik

coppelia
Site Admin
Posts: 7838
Joined: 14 Dec 2012, 00:25

Re: Torque control

Post by coppelia »

Hello Erik,

when you say that it did not work (in the beginning of your message), what didn't work, or what was the result?

If there are functions that are not directly supported via the remote API client, then you have two possibilities:
  • you could extend the remote API, which is not that easy
  • you could implement the command inside of a child script that will act as a proxy for the remote API client: basically your remote API client will send a signal to the script that will then execute a command for it.
Cheers

erik
Posts: 5
Joined: 03 Dec 2014, 15:54

Re: Torque control

Post by erik »

It seems I forgot to switch the velocity sign, your previous explanation really helped, thanks! However, this way of doing joint torque control is not accurate enough for me: the gravity compensation is a bit unstable. So I'd prefer using simAddForceAndTorque where I can do the 0 reference velocity trick as I explained in my previous post.

In that case, your second suggestions sounds like a good idea. So correct me if I'm wrong: this means I would use an existing remote API function to send the desired torque from Matlab to a child script, and then in that child script, use simAddForceAndTorque to apply that torque? I'm not really sure what remote API function I would use for this. Do you have a suggestion?

Thanks for your help,

Erik

coppelia
Site Admin
Posts: 7838
Joined: 14 Dec 2012, 00:25

Re: Torque control

Post by coppelia »

yes, that is correct. You could for instance do:

On the remote API client side (e.g. in C/C++):

Code: Select all

float forceVectorToApply[3]; // a force vector initialized to what you want
simxSetStringSignal(clientId,"myVector",(simxChar*)forceVectorToApply,3*sizeof(float),simx_opmode_oneshot);
Inside of a non-threaded child script:

Code: Select all

if (sim_call_type==sim_childscriptcall_initialization) then
	lastVector={0,0,0}
end

if (sim_call_type==sim_childscriptcall_actuation) then
	local signal=simGetStringSignal('myVector')
	if signal then
		lastVector=simUnpackFloats(signal)
	end

	-- Apply your vector here:
	simAddForceAndTorque(shapeHandle,lastVector)
end
Cheers

erik
Posts: 5
Joined: 03 Dec 2014, 15:54

Re: Torque control

Post by erik »

That is just what I needed, it works perfectly!

I've put it in a threaded script and together with some synchronization triggers, the control from Matlab does exactly what I expect it to do.

Thank you for quick replies!

Post Reply