CentroEPiaggio / kuka-lwr

Software related to the KUKA LWR 4+: for real and for simulation.
The Unlicense
101 stars 81 forks source link

[FRI quesition] Joint torque commands not executed on robot #93

Closed balakumar-s closed 7 years ago

balakumar-s commented 7 years ago

I want to send joint torque commands to the LWR. Currently, I have the robot in joint impedance mode. I can send joint position commands and the robot moves. If I send joint torques, the robot does not move ( the commands are not executed on the robot).

  1. Do you have to be at 1khz to send joint torque commands? ( currently my control rate is 100hz- friopen(10))
  2. How do you send joint torque commands?( Do I have to do something specific in the krl?) Thanks.
marcoesposito1988 commented 7 years ago

Hi @balakumar-s,

I am not using the robot at the moment, but I think that the last big refactoring (not done by me) did not leave the effort command in a working condition: there is no interface type which triggers the effort control method. As you can see here, pure effort control will be activated when the control strategy is JOINT_EFFORT; however, looking here, that strategy will never be activated.

Since there are more possible strategies than standard interface types in ROS, fixing this would require writing a new interface type like here, then fix the getNewControlStrategy function and the controllers which might use this strategy to use the new interface.

You are more than welcome to work on the issue. I am not investing much more effort into this since we are changing our robot soon.

graiola commented 7 years ago

From what I see in the code highlighted by @marcoesposito1988 , you could use the JOINT_IMPEDANCE control strategy to perform a JOINT_EFFORT control, just set the stiffness to zero and the joint_set_pointcommand to the current joints position.

@marcoesposito1988 do you think it would work?

balakumar-s commented 7 years ago

@graiola That's exactly what I attempted. I even tried sending a single torque value to the motors to check if a torque is exerted by the motors, but that did not work. I am currently running FRI at 10ms. Maybe it works only at 1ms?

marcoesposito1988 commented 7 years ago

Yes, you can basically achieve effort-based control by setting the stiffness to zero and constantly actualising the setpoint (the commanded pose) to the measured pose. Do not forget that step in automatic mode, or the robot might jump back when you switch back to position control!

However, that is just theory. I never managed to get it to work: I guess I had the same problem as @balakumar-s.

balakumar-s commented 7 years ago

@marcoesposito1988 Thanks, I am able to send joint torques now. Previously I was sending very little torques. The robot needs a minimum of 0.5 to overcome the internal gravity compensation. It works at 10ms. I have setup a simple PD torque controller. Currently its very compliant but sufficient for my work. Here is a video of the controller: https://youtu.be/9p9ymOskieE