epfl-lasa / iiwa_ros

ROS Meta-package for controlling KUKA IIWA
GNU General Public License v3.0
133 stars 41 forks source link

Question for dynamic parameters of the robot #60

Closed ghost closed 3 years ago

ghost commented 3 years ago

Hello,

This question is about the correctness of the inertia parameters of the kuka robot. I know that there was a similar discussion, and the correct/official inertia values from kuka is not known. However, I would like to know if the inertia values from the urdf is accurate enough to perform torque-based control, or should I anticipate any trouble if I use the inertia values from the urdf?

Thanks a lot.

costashatz commented 3 years ago

However, I would like to know if the inertia values from the urdf is accurate enough to perform torque-based control, or should I anticipate any trouble if I use the inertia values from the urdf?

I have used the inertia values from the URDF to do torque-based control in KUKA and never encountered big issues. Note you have to be careful what torque to send: KUKA is always adding the gravity compensation to the command that you send.

matthias-mayr commented 3 years ago

Where do the values come from? I always thought that the 14kg version values come from this publication, but the ones they mention in the appendix differ from the ones in the urdf.. There is this discussion in iiwa_stack that uses the same parameters. I never took the time to finish the identification for the 7kg arms that we have though.

costashatz commented 3 years ago

Where do the values come from? I always thought that the 14kg version values come from this publication, but the ones they mention in the appendix differ from the ones in the urdf.. There is this discussion in iiwa_stack that uses the same parameters. I never took the time to finish the identification for the 7kg arms that we have though.

We just copy-pasted those values from iiwa_stack. I never actually tested how accurate they are. Nevertheless, I have been using the code for torque-based control (with model-based controllers where the model comes from the URDF) and never experienced very bad behavior in both iiwa14 and iiwa7 (mostly iiwa14 to be honest).

I remember that @fkhadivar did some work on identifying the model for iiwa14, and I guess we can do the same procedure for iiwa7. @fkhadivar can you share the work/code of this?

ghost commented 3 years ago

Thank you all for the quick reply. I have two questions now for the forwardKinamtics:

1) The calculated FK from rbdyn (python version RBDL) does not match with the one showing on the KUKA teach pendant; At joint position given in rad: np.array([-0.169909764104478, -0.050990719776016366, -0.00956688692270681, -1.4148164265134209, -1.8270859752610134, 0.49395571535575167, 1.0900568146034129]) or deg: np.array([ -9.73511238, -2.92155304, -0.54814224, -81.06301002, -104.68431519, 28.30157776, 62.45565491]) The Cartesian Pos I have for xyz with rbdyn is: 0.457527, -0.141996, 0.899215 (m) However, the teach pendant gives me the following xyz position under this joint position 0.47681, -0.15762, 0.90697 (m)

2) Therefore, to findout which value is "more" accurate then I used the services under the iiwa_tools (thank you). However, I'm having trouble sending Float64multiarray with rospy service. I wonder if you may help me to debug the following code to get the service working. I believe this would also benefit the other potential users. I want to apologize first since I have to use python for this project for many reasons.

from iiwa_tools.srv import *
class KukaSim(object):
    def __init__(self):
        self.loop_period = 0.01
        rospy.wait_for_service('iiwa/iiwa_fk_server')
        self.fk_srv= rospy.ServiceProxy('iiwa/iiwa_fk_server',GetFK)
    def testFK(self,data):
        result = GetFKResponse()
        request = GetFKRequest()
        array = []
        for i in range(7):
             array.append(self._q[i]) #self._q contained the current joint position 
        request.joints.layout.dim = Float64MultiArray(data=array) # how to put the joint position into the request?
        try:
             result = self.fk_srv(request)
        except rospy.ServiceException as exc:   
             print("Service did not process request: " + str(exc))
if __name__ == "__main__":
    rospy.init_node("runKuka")
    obj = KukaSim()
    try:
        rospy.Timer(rospy.Duration(obj.loop_period), obj.testFK )
        rospy.spin()
    except rospy.ROSInterruptException:
        pass

It would be great if you could let me know which calculation of the FK is accurate or how I may use the fk service provided in the iiwa_tools. I would really appreciate any help. Thanks.

costashatz commented 3 years ago

2. However, I'm having trouble sending Float64multiarray with rospy service

Here's a quick example of using the messages for FK:

from iiwa_tools.srv import GetFK

fk_service = '/iiwa/iiwa_fk_server'
rospy.wait_for_service(fk_service)
get_fk = rospy.ServiceProxy(fk_service, GetFK)
seed = Float64MultiArray()
seed.layout = MultiArrayLayout()
seed.layout.dim = [MultiArrayDimension(), MultiArrayDimension()]
seed.layout.dim[0].size = 1
seed.layout.dim[1].size = 7
seed.data = [0., 1., 0., -1., 0., 1., 0.]
resp = get_fk(joints=seed)
sol_pose = resp.poses[0]
print('sol:', sol_pose)
  1. The calculated FK from rbdyn (python version RBDL) does not match with the one showing on the KUKA teach pendant;

No idea what this KUKA teach pendant is. I was using the code above for FK (and similar one for IK) for doing dual arm manipulation with <1mm accuracy. I also made numerous tests and never saw a mismatch between reality and the model (same values to 1e-8). I doubt that there is a big kinematic error in the model.

JimmyDaSilva commented 3 years ago

No idea what this KUKA teach pendant is.

That is simply the IIWA's Smart Pad. You can see Kuka's FK estimation on it. I guess @Thompson104 is taking it as the ground truth to validate your FK calculation with rbdyn.

@Thompson104 Be careful, you might be looking at the FK for the "flange" frame on the Smart Pad, while comparing it to a different end_effector frame (link_7 maybe) with rbdyn

ghost commented 3 years ago

Thank you guys for the quick response. Really appreciate it. I think the smart pad shows the FK of the flange frame and this caused the FK calculation difference.

1) Currently I have a tool attached to the iiwa end-effector (around 2kg). I have used the loadDataDetermination function from kuka. However, it looks like this function cannot provide an accurate estimate of the inertial parameters since the robot would "fall" when the tool is attached and the estimated parameters changes by more than 10% everytime I re-run the loadDataDetermination. To solve this problem, I can estimate the inertia parameters (very hard to get accurate results); or, I can increase the motion stiffness/damping either from the java program or from the commanded torque interface (via ROS). However, increasing the stiffness/damping causes some issues for my force and moment control ( the gains are very hard to tune). I'm wondering if you guys have similar experience and would appreciate your suggestions on how to run motion control with payload.

2) Do you have a reference for this package or how would I cite this repo properly?

Thanks for providing this repo. I promise those two questions would be my last questions at least for the current time period.

costashatz commented 3 years ago
  1. Currently I have a tool attached to the iiwa end-effector (around 2kg). I have used the loadDataDetermination function from kuka. However, it looks like this function cannot provide an accurate estimate of the inertial parameters since the robot would "fall" when the tool is attached and the estimated parameters changes by more than 10% everytime I re-run the loadDataDetermination. To solve this problem, I can estimate the inertia parameters (very hard to get accurate results); or, I can increase the motion stiffness/damping either from the java program or from the commanded torque interface (via ROS). However, increasing the stiffness/damping causes some issues for my force and moment control ( the gains are very hard to tune). I'm wondering if you guys have similar experience and would appreciate your suggestions on how to run motion control with payload.

You need to use this java file (and define and select the gripper/tool accordingly) if you want the gripper to be taken into account. Can you verify that you did this?

2. Do you have a reference for this package or how would I cite this repo properly?

You mean citing the package in a scientific publication?

ghost commented 3 years ago

1) Thank you @costashatz, I'm able to confirm that the provided java file is able to provide gravity compensation after the loadDataDetermination.

2) Yes, I mean citing a this repo in an academic paper.

Thanks.

ghost commented 3 years ago

Please re-open this issue and add a reference if you have any, otherwise I'm closing this issue.

Thank you for your help.

costashatz commented 3 years ago

2. Yes, I mean citing a this repo in an academic paper.

I do not really have a way to cite this repo. Let me create something quickly and update the README.