Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Torque control not working #232

Closed
Hydran00 opened this issue Dec 2, 2024 · 16 comments
Closed

Torque control not working #232

Hydran00 opened this issue Dec 2, 2024 · 16 comments
Labels
bug Something isn't working

Comments

@Hydran00
Copy link
Contributor

Hydran00 commented Dec 2, 2024

Hi,

thank you for your work!

We managed to install everything smoothly and the position control demo worked fine (Humble branch), but encountered an issue during the torque control demos: the robot (LBR IIWA 14 R820) did not move.

After some trials, we managed to make the torque demo work by adding the following line here

command_.torque = command_target_.torque;

It is very strange, since there are no open or closed issues reporting this problem. Do you have any suggestion?

@mhubii
Copy link
Member

mhubii commented Dec 3, 2024

hi @Hydran00 , no worries. Quick question, did you set the client_command_mode to torque here:

client_command_mode: position # the command mode specifies the user-sent commands. Available: [position, torque, wrench]

Also make sure to

  • Set FRI send period to 2ms or less
  • Calibrate load data if tools are attached (this is undocumented right now)

There is currently an issue with forwarding the joint states in torque / wrench command mode, #226

@Hydran00
Copy link
Contributor Author

Hydran00 commented Dec 3, 2024

Thank you for you reply.
I followed the guide, therefore I correctly set the send period and command mode to torque.

@mhubii mhubii added the bug Something isn't working label Dec 3, 2024
@mhubii
Copy link
Member

mhubii commented Dec 3, 2024

okay I see, this is a bug then introduced in #225. Seems also wrong for wrench command mode

if (!joint_position_filter_.is_initialized()) {

thanks for sharing @Hydran00. If you could open a PR that adds the mentioned line, would be great! Ideally this PR would target rolling.

Add

  • torque_command.cpp
command_.torque = command_target_.torque;
  • wrench_command.cpp
command_.wrench = command_target_.wrench;

@mhubii mhubii closed this as completed Dec 3, 2024
@mhubii mhubii reopened this Dec 3, 2024
@Hydran00
Copy link
Contributor Author

Hydran00 commented Dec 3, 2024

Ok, I will do it soon 👍

matteodv99tn added a commit to idra-lab/lbr_fri_ros2_stack that referenced this issue Dec 4, 2024
matteodv99tn added a commit to idra-lab/lbr_fri_ros2_stack that referenced this issue Dec 4, 2024
matteodv99tn added a commit to idra-lab/lbr_fri_ros2_stack that referenced this issue Dec 4, 2024
matteodv99tn added a commit to idra-lab/lbr_fri_ros2_stack that referenced this issue Dec 4, 2024
@Hydran00
Copy link
Contributor Author

Hydran00 commented Dec 4, 2024

By the way, we were trying to implement our own cartesian impedance controller to be able to change the stiffness achieving variable impedance control by using the robot in gravity compensation. To achieve gravity compensation, we set every stiffness gains to zero in the LBRServer.java here.

In gravity compensation we were facing an issue on the pendant called Illegal axis delta detected and we managed to bypass it by setting the parameter open_loop to false in your interface.

The problem we were facing when sending zero torque to this hardware interface is that the robot has a strange behaviour: it seems to drift a bit even when no external forces are applied.
Also, it has a lot of joint friction and poor tracking performances when we add our overlay torque for the impedance tracking of a trajectory.

Do you think know other way to achieve gravity compensation?

You can check our repository if you are interested in the implementation of the controller.

@mhubii
Copy link
Member

mhubii commented Dec 4, 2024

happy to try the controller. I haven't encountered Illegal axis delta detected before. Could you share a quick readme so I can try run it?

The drift on the KUKAs is common since the inverse dynamics model isn't perfect. Adding a threshold somewhere can help

@Hydran00
Copy link
Contributor Author

Hydran00 commented Dec 4, 2024

Ok, I will update the readme so that you can replicate as soon as I can. 👌

What do you mean by "the inverse dynamics model isn't perfect"? You mean that the FRI does not provide an accurate dynamics model?

Also, you mentioned that we should calibrate the load data, how can we achieve that? Do you mean by using the robot mastering button on the teach pendant? We do not have tools attached, but maybe we can try calibrating the sensors anyway.

@Hydran00
Copy link
Contributor Author

Hydran00 commented Dec 4, 2024

We created a repository to implement the Cartesian impedance control, with a small guide on how to make it work. As I told you, I cannot test it on the hardware, but it was working last week, even if with poor perfomances.

mhubii added a commit that referenced this issue Dec 4, 2024
github-actions bot pushed a commit that referenced this issue Dec 4, 2024
(cherry picked from commit 2cc7ae8)
@mhubii
Copy link
Member

mhubii commented Dec 4, 2024

great, will check this out. Thank you again for raising the issue and fixing it! Going to add some doc for calibrating load data soon. Closing this issue for now

@anselmo-parnada
Copy link

Hi @Hydran00,

I am also trying to implement a Cartesian Impedance controller on top of this project.

The problem we were facing when sending zero torque to this hardware interface is that the robot has a strange behaviour: it seems to drift a bit even when no external forces are applied.

I have made a similar observation to above in that executing a position hold command in (joint or Cartesian) impedance mode with zero stiffness and no external forces applied causes the robot drift away from the initial position. In fact, it will accelerate away from the initial position, triggering the safety system to initiate a safety stop.

For our robot, I think it is due to the actuator A1, and to a minor extent A4, having some sort of bias to always apply enough torque to cause motion in the negative direction relative to the rotation axis. I do not think it is because of the robot performing gravity compensation with an imperfect dynamics model because the drifting also occurs when the robot starts in the mechanical zero position. I do not expect actuator A1 to apply any significant compensatory torques in the mechanical zero position.

Perhaps this is an issue specifically with our robot due to wear-and-tear, or if it is something others have experienced. I wonder if this aligns with your observations, and how you were able to overcome this issue, if you have.


Apologies @mhubii if this off-topic. I wasn't sure where else I could share this observation.

@mhubii
Copy link
Member

mhubii commented Dec 11, 2024

no worries @anselmo-parnada, I think it is important to have this discussion and I can confirm that the LBR, when controlled with zero stiffness, drifts and potentially overshoots. Two issues (imho):

  1. Load data calibration. If load data isn't calibrated, the LBR's inverse dynamics model is off (it doesn't know anything is attached to it). The documentation for how to do this is missing Document load data calibration #235. This should and will be added.
  2. The inverse dynamics model of the LBR is not perfect. I am not sure how to address this, or whether this is something KUKA needs to improve.

@Hydran00
Copy link
Contributor Author

Hi @anselmo-parnada,

me and my team tried the gravity compensation with the robot in its mechanical zero position and our robot does not drift, however as soon as we move it, it starts drifting.
If you are facing the Illegal axis delta error, you can turn off open_loop, i.e. (open_loop: false) in the lbr_system_config.yaml, but the robot behaviour seems to change: it looks like there is a stiction force on each joint that prevents it from being smooth.

You can easily check this by trying moving the robot base (joint A1) in the two different case. Please tell me if you have the same behaviour. 🙂

@anselmo-parnada
Copy link

anselmo-parnada commented Dec 11, 2024

Hey @mhubii, thanks for the response.

  1. Load data calibration. If load data isn't calibrated, the LBR's inverse dynamics model is off (it doesn't know anything is attached to it). The documentation for how to do this is missing Document load data calibration #235. This should and will be added.

By calibrating the load data, are you referring to the tool load calibration program accessible via the SmartPad? I have so far only been testing the robot without a tool attached to it's mounting flange, so there is no load to calibrate, in principle. Are you suggesting calibrating the load of an empty tool to "correct" the dynamics model?

I tried this before and gotten very strange values from calibration program. At best, I think this would "correct" the dynamics model only for joint configuration that you start the calibration process. However, this will not solve the underlying issue.

2. The inverse dynamics model of the LBR is not perfect. I am not sure how to address this, or whether this is something KUKA needs to improve.

Perhaps they do not calibrate the dynamics for each unique robot they produce, so the dynamics model will always be inaccurate. Perhaps they do, and the dynamic properties of the robot gradually deviates from the model over time due to wear-and-tear. How old are the robots you guys are using?

@anselmo-parnada
Copy link

anselmo-parnada commented Dec 11, 2024

Hi @Hydran00,

me and my team tried the gravity compensation with the robot in its mechanical zero position and our robot does not drift, however as soon as we move it, it starts drifting.

Just tried this 3 times. The first time, it remained stationary and only began to drift when I moved it, similar to you. The next 2 times, it began drifting immediately after the position hold command was initiated.

Does your robot like to drift in a particular direction? Our robot's A1 joint likes to turn clockwise (looking from above), exclusively, no matter the starting configuration. Wonder if your robot does the same.

If you are facing the Illegal axis delta error, you can turn off open_loop, i.e. (open_loop: false) in the lbr_system_config.yaml, but the robot behaviour seems to change: it looks like there is a stiction force on each joint that prevents it from being smooth.

I am already using open_loop: false, so I've not been having the Illegal axis delta error. When do you experience the stiction force issue? I'm not clear on what steps to take to reproduce this issue. Please let me know, thanks!

@Hydran00
Copy link
Contributor Author

Our robot tends to have strange unwanted motion for joints A4 and A5 but not in A1. They also rotate every time toward the same direction as in your case.

However, we solved the stiction problem: it was due to the fact that we commented these lines in our fork.

if (!joint_position_filter_.is_initialized()) {
joint_position_filter_.initialize(state.sample_time);
}
joint_position_filter_.compute(command_target_.joint_position, command_.joint_position);

We tried again our cartesian impedance control and this time the behaviour was much better. Even though the gravity compensation (i.e. stiffness set to zero) is not good, this errors are compensated by the torque contributes generated by the position error. If you want, you can give it a try. 🦾

@mhubii
Copy link
Member

mhubii commented Dec 13, 2024

By calibrating the load data, are you referring to the tool load calibration program accessible via the SmartPad?

yes, been referring to that @anselmo-parnada.

How old are the robots you guys are using?

The robot that we are using is about 5 years old @anselmo-parnada.

However, we solved the stiction problem: it was due to the fact that we commented these lines in our fork.

When this line is removed, the target position remains unchanged, maybe that stops the observed drifting @Hydran00. Could there somehow be a bug in the demo code, so that the commanded position changes?

self._lbr_torque_command.joint_position = deepcopy(

If you want, you can give it a try. 🦾

Will try out this controller over the weekend @Hydran00. Hopefully I can replicate the issues.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

No branches or pull requests

3 participants