frankaemika/franka_ros

Cartesian impedance example controller errors simulation vs real robot

Opened this issue · 4 comments

I was mostly developing my controllers by now using the gazebo simulation. However I was very disappointed, when I saw the results on the real robot. Getting down on it, I found that even the cartesian impedance controller from the examples show significant errors (translational). Whereas they seem to work fine on the simulation.
To make the problem reproducable, I started a fork with a small modifications to the controller giving out the error, play a recorded bag and added a new launch.

For simulation:roslaunch franka_example_controllers issue_robot_inexact.launch operation_type:=simulation
Gives roughly this expected result (error drops rapidly when equilibrium pose stops moving and aproximates zero)
simulation_error

Before starting with the real robot I removed the gripper to rule out an incorrect weight of the endeffector and set it's mass etc. using the set_load service to zero.
For robot: roslaunch franka_example_controllers issue_robot_inexact.launch operation_type:=robot robot_ip:=LOCAL_ROBOT_ADRESS
Gives roughly this rather bad result (error drops rapidly when equilibrium pose stops moving, but aproximates a pose some centimeters from the correct pose)
robot_error

I suspect, that for joint effort control we need to take the gravity of the joints into account. So I tried to get the gravity like in franka_hw_sim
However this also did not quit the trick:
roslaunch franka_example_controllers issue_robot_inexact.launch operation_type:=robot robot_ip:=LOCAL_ROBOT_ADRESS add_gravity:=true
robot_error_with_gravity

Hopefully I just miss something, as this is a pretty basic functionality.

I can understand that you are a bit frustrated. I am not quite sure what you are trying to achieve but I guess you want to move the robot in cartesian space? A simple solution would be to use the CartesianPose interface instead of the Effort interface. This would eliminate all inaccuracies. However, this interface is currently only implemented on the real robot an not in Gazebo. Looking at your graphs my guess would be that these spikes are the result of the joint friction. The Cartesian impedance controller is also more of an example on how to use the effort interface instead of a way to precisely move the robot. However, you could try to modify the controller gains, to make it more precise

Hey marcbone,
What I do want to achieve:

  1. Build a controller, which moves smoothly and exact to given cartesian coordinates using joint effort commands.
  2. Simulate the movements of the robot correctly to test my controllers during the development cycles.

At the moment running my tests using the simulation result in false-positivs. It says my contollers works when the controller does not with the real robot.

So I'm not worried about the spikes in the error. One cannot avoid these as even the best robot won't move instantly. I'm worried about the very bad overall performance for the real robot seen in the two last pictures.
But to be clear, I don't want to correct my controller, I want to correct the gazebo simulation first so it makes the robot move wrongly as in reality. Than I can develop and debug it with the simulation.

To the question, why I don't want to use the cartesianPose commands:
I implemented my first controllers using the cartesianPose commands. However, I constantly run into joint (position, speed and acceleration) limit errors. I found that when using the joint effort commands I can avoid these by truncating the commands before sending.
For cartesianPose commands, I can only reduce the errors by slowing down the robot using dynamic_rel. Obviously such a controller I want to develop here is running in the black box. So my motivation having such a controller is also to add cartesianPose commands to the gazebo simulation. Such a controller is also no company secret or cutting edge science as all the parameters of the robot are given.
Moreover the robot is at a place where I don't want to go that often so I want to test as much as possible in the simulation.

I will look, whether I can implement a controller using cartesianCommands and compare the errors.

The last days I debugged the problem i bit more in detail. The answer is probably joint friction!
When debugging the controller using the real robot: I had a look at: /franka_state_controller/franka_states/tau_J_d (the joint torque without gravity the controller commands) and /franka_state_controller/franka_states/tau_J (the actual joint torque with additional gravitation compensation from the black box).
As expected tau_J_d was not all zero, so the controller acutally tries to move the Joints, but nothing is moving. As if there was friction on the joints which make sense. It also makes sense, that there is no such effect in the simulation.

The documentation of libfranka states that when using an external controller than the black box is doing gravity and friction compensation. So I highly suspect, that the friction compensation is to weak.

The questions would be now:

  1. How to find the correct friction of the real robot. Maybe this paper could help but I didn't get it completely by now. Or are there any PR open by now?
  2. How to modify the gazebo simulation to model the correct friction of the joints. Or do we even need something like this?

Note that this repo appears to represent that paper's primary dynamic parameters, but not the friction model.
Made a brief mention of this in https://www.franka-community.de/t/panda-dynamic-model/4573/3