Difference in Cartesian values calculated by FK and reported by RSI
Hi all, I have encountered a problem. I'm using RSI to control KR10R1100 and using the URDF in kuka_experimental package. I have noticed that the Cartesian xyz values(for tool0) that I calculate based on the joint values (FK) is different from the values reported by RSI. As long as the fang is parallel to the floor the error is small but when we have rotation about 45 degree it is getting huge(about 2 to 6 mm in each x,y,z) The following graph shows the difference in bottom left in meter.
Any idea?
Edit: some news:
- Kuka side: before KRC 4 and version 8.5 they used xxx.PID files to store DH parameters for calibrated robots. After that they don't optimize the robot by finding optimized DH params. they are using another method somehow elastic frames and they store the result encrypted in xml format so there is no access to the data.
- in parallel, I modified this idea and using kuka rsi ist_cartesian value as sensor data. After lots of tries with different calibration paths, the resulted offset was as following:
- joint_a1_x: -8.04105e-08
- joint_a1_y: -3.72801e-07
- joint_a1_z: 9.19109e-07
- joint_a2_x: -9.67871e-07
- joint_a2_y: 1.09999e-07
- joint_a2_z: 9.19109e-07
- joint_a3_x: -8.58927e-07
- joint_a3_y: 1.09875e-07
- joint_a3_z: -9.13359e-07
- joint_a4_x: -7.1247e-08
- joint_a4_y: 1.10038e-07
- joint_a4_z: -0.0100007
- joint_a5_x: -7.01281e-08
- joint_a5_y: 2.90021e-08
- joint_a5_z: -2.38001e-07
- joint_a6_x: 0.0100001
- joint_a6_y: 2.80272e-08
- joint_a6_z: -4.06979e-07
I found out the correction on a4_z and a6_x is really huge. about 10 mm. Then I checked the urdf and kuka manual:
so it seems that out urdf is wrong:
<joint name="${prefix}joint_a4" type="revolute">
<origin xyz="0 0 0.035" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="${-DEG2RAD * 185}" upper="${DEG2RAD * 185}" velocity="${DEG2RAD * 381}"/>
</joint>
<joint name="${prefix}joint_a6" type="revolute">
<origin xyz="0.080 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_5"/>
<child link="${prefix}link_6"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="${-DEG2RAD * 350}" upper="${DEG2RAD * 350}" velocity="${DEG2RAD * 615}"/>
</joint>
I have the KUKA kr10r1100-2. May this 2 at the end has a meaning related to this difference?
we don't see anything as you're linking to an off-site file. You cannot include images like that.
Please attach your image to your question directly, I've given you sufficient karma.
thanks. I have updated it with the image.