ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Difference in Cartesian values calculated by FK and reported by RSI

asked 2021-03-01 07:35:55 -0500

behbot gravatar image

updated 2021-03-04 12:52:09 -0500

gvdhoorn gravatar image

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.

image description 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:

image description

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?

edit retag flag offensive close merge delete

Comments

The following graph shows the difference in bottom left in meter.

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.

gvdhoorn gravatar image gvdhoorn  ( 2021-03-01 09:55:25 -0500 )edit

thanks. I have updated it with the image.

behbot gravatar image behbot  ( 2021-03-01 10:00:38 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-03-01 10:10:29 -0500

gvdhoorn gravatar image

updated 2021-03-04 12:57:57 -0500

It could be there is a mistake in the provided _macro.xacros, but it would be good to get some more info.

One thing to keep in mind: the _macro.xacro models the ideal or nominal robot. If yours is (kinematically) calibrated and you haven't updated the xacro, the robot_state_publisher will not know about this and FK will not result in the same values as the robot reports.


Edit:

As long as the fang is parallel to the floor [..]

off-topic, but: that sounds like a dangerous robot ;)


Edit 2:

I have the KUKA kr10r1100-2. May this 2 at the end has a meaning related to this difference?

yes, I believe that's the cause of what you see.

From the online datasheet of the KR10 R1100 sixx (0000210360_EN.pdf, here):

non -2 KR 10 R1100 sixx

Notice the translation in Z for joint_4 is 0.35, and the translation in X for joint_6 is 0.80, as they are in the _macro.xacro.

It would appear the -2 has some links with slightly different lengths.

This would require adding support for the -2 variant to the kuka_kr10_support package. Would you be willing to contribute that?

edit flag offensive delete link more

Comments

Thanks for the answer. That's exactly what I also have doubt about. Is there any way to get this calibration data from KUKA controller and putting it is the XACRO or should I do a calibration procedure like robot calibration package by providing RSI Cartesian values as sensor data.

and about the _macro.xacro file, I'm using this file: https://github.com/ros-industrial/kuka_experimental/blob/indigo-devel/kuka_kr10_support/urdf/kr10r1100sixx_macro.xacro

behbot gravatar image behbot  ( 2021-03-01 10:20:36 -0500 )edit

Is there any way to get this calibration data from KUKA controller

Could be, but I would not know how right now.

I would suggest you ask your KUKA sales/support person -- and then report back here.

But first: try to ascertain whether your robot has been calibrated.

should I do a calibration procedure like robot calibration package by providing RSI Cartesian values as sensor data.

I'm not sure how that would help. Edit: yes, this could work, but should not be your first approach I believe. See below.

If your robot has been calibrated, getting the data out of the controller and updating the _macro.xacro would be the correct course of action imo (related discussion on the ros-industrial/motoman tracker: ros-industrial/motoman#390). .

If that's not possible, then I'd start looking at other options -- which would essentially be work-arounds.

gvdhoorn gravatar image gvdhoorn  ( 2021-03-01 10:41:01 -0500 )edit

Thanks @gvdhoorn. I will do both in parallel and inform the results here.

behbot gravatar image behbot  ( 2021-03-02 09:16:16 -0500 )edit

I would really suggest retrieving the values from the controller -- if your robot is in fact calibrated.

The result of robot_calibration, as nice as the package is, is most likely always going to be an approximation.

gvdhoorn gravatar image gvdhoorn  ( 2021-03-02 09:34:42 -0500 )edit

Thanks @gvdhoorn. Sorry for may late reply. It is a bad phase for my project and lot's of thing to do! Yes for sure. I will make a new package for kr10r1100-2 and will send a pull request in the repository as soon as possible.

behbot gravatar image behbot  ( 2021-03-10 06:33:04 -0500 )edit

I will make a new package for kr10r1100-2 [..]

If the -2 is a new variant, then we should probably add the files for the variant to the kuka_kr10_support package instead of creating a new package. You could potentially even reuse most of the meshes (ie: .stls) of the non--2 variant.

gvdhoorn gravatar image gvdhoorn  ( 2021-03-10 06:48:16 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-03-01 07:35:55 -0500

Seen: 148 times

Last updated: Mar 04 '21