ros-industrial / motoman

ROS-Industrial Motoman support (http://wiki.ros.org/motoman)
146 stars 193 forks source link

sda10f: dimensions in URDF does not match specifications #232

Closed hsd-dev closed 4 years ago

hsd-dev commented 6 years ago

While working on https://github.com/ros-industrial/ros_industrial_issues/issues/28 for motoman, I noticed that the dimensions in URDF for SDA10f differ from that in specification: page 32.

For eg: according to the document distance between vertical axes of arm_left_link_2_l and arm_right_link_2_l is 530mm but

$ rosrun tf tf_echo /arm_left_link_2_l /arm_right_link_2_l

shows

At time 1532606439.014
- Translation: [0.000, -0.506, 0.000]
- Rotation: in Quaternion [0.000, -0.000, 1.000, -0.001]
            in RPY (radian) [-0.000, 0.000, -3.140]
            in RPY (degree) [-0.000, 0.000, -179.909]

i.e. 506mm. Similarly, arm_right_link_4_u and arm_right_link_2_l have an offset of 360mm

$ rosrun tf tf_echo /arm_right_link_4_u /arm_right_link_2_l

shows

At time 1532606196.314
- Translation: [0.000, -0.350, 0.054]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
            in RPY (radian) [0.000, -0.000, 0.000]
            in RPY (degree) [0.000, -0.000, 0.000]

i.e. 350mm

This seems to be the case with other dimensions as well. What is the reference used for the URDF?

gavanderhoorn commented 6 years ago

This package was introduced by @thiagodefreitas in 45bd3273. According to the package manifest added in that commit, the reference is/was: http://www.motoman.com/datasheets/sda10f.pdf. No mention of which version or document nr though, and that link doesn't load a pdf any longer it appears.

Current version is here.

Note btw that for many urdfs in ROS (not just ROS-I), the inter-joint-origin distances do not always correspond to what the datasheet(s) list.

It's considered adequate if the total arm length (ie: from root to the last link) is correct.

Personally I do like it if everything matches the datasheet (as it also sometimes allows to transform points into link-local coordinate systems), but it's not always possible.

shaun-edwards commented 6 years ago

@ipa-hsd, thanks for pointing this out. At Plus One, we "check" the URDF by checking the transform from base to tip in ROS and on the robot teach pendant. We have found issues in the past with the data sheets and CAD models. When this occurs, we reach out to Motoman to get the right parameters from the controller.

EricMarcil commented 6 years ago

In its default position the SDA10 is in a T position with both arms stretch out on each side. The X-axis if pointing forward and the Z-axis up. The distance from the base rotation axis to the center of the arms rotation center is 100 mm along the X-axis. The distance from the center of the arms (or torso) to the L-axis (axis 2) is 265 mm The distance from the L-axis (axis 2) to the U-axis (axis 4) is 360 mm The distance from the U-axis (axis 4) to the B-axis (axis 6) is 360 mm The distance from the B-axis (axis 6) to the flange is 155 mm

This matches the datasheet. The distance between the arms (560 mm) is not explicitely on the datasheet. There is a value of about 505 mm which is related to the base dimension but I could see it as being wronfully interpreted as being the distance between the arms.

I hope this helps.

Eric Marcil Yaskawa America Inc.

gavanderhoorn commented 6 years ago

I've just posted an enhancement request/proposal that could make checking these sort of things easier/feasible: #238.

hsd-dev commented 6 years ago

None of the dimensions match except for

The distance from the base rotation axis to the center of the arms rotation center is 100 mm along the X-axis.

Also as @EricMarcil wrote:

This matches the datasheet. The distance between the arms (560 mm) is not explicitely on the datasheet. There is a value of about 505 mm which is related to the base dimension but I could see it as being wronfully interpreted as being the distance between the arms.

Maybe this was the confusion, since the distance between both L axes is in fact 505mm as per tf data.

@gavanderhoorn wrote:

I've just posted an enhancement request/proposal that could make checking these sort of things easier/feasible: #238.

This would be interesting.

EricMarcil commented 6 years ago

@ipa-hsd, Sorry I was away on vacation and didn't have a chance to have a close look at the SDA10 model until now. You are correct, that model has some errors. I'm not sure where it came from, it's an old model and doesn't look as if it follows the new model structure.
I've also realized that in my previous posting I said the distance from center to the L-axis rotation is 265 (which is correct) but then after I say the distance between arms is 560, which is wrong that should have been 530. Did you manage to make corrections to have a usable model? There is also a model in the motoman_experimental which is noted as being a clean-up version that correct the tool0 position. I haven't looked into the details of it yet... Let me know where you are at and I should have a bit more time to help out.
I would like to eventually update the model on github for future users...

EricMarcil commented 6 years ago

I just inspected the csda10f model from the motoman_experimental branch. It is better (and the MoveIt package actually works) but I still found a 20 mm error on end of the arm. To correct it, I changed the arm_macro.xacro joint_7_t origin to: origin xyz="0 0.098 -0.015" rpy="1.57 0 0"

I still don't quite like the way the model is build because distance between the joints are broken up between two joints. You basically need to add the Y value of the previous joint with the Z value of the next one to match the distance of the diagram. The SDA10F arm are essentially the assembly of two SIA10F arms. If you look at the SIA10F structure, it is a lot cleaner. But in order to fix the SDA10F to match it, the origin of the 3D model files (stl) will need to be repositioned.

hsd-dev commented 6 years ago

I tested the URDF from moveit_experimental repo as well.

origin xyz="0 0.098 -0.015" rpy="1.57 0 0"

With this change, the values match with that of datasheet.

asierfernandez commented 5 years ago

We've been also working around this issue with sda10f robot. The model described motoman_sda10f_support is far away from official sda10f model. Find bellow updated transforms according to the 3D CAD model from previous link.

Due to there isn't any update about sda10f in [motoman_experimental] https://github.com/ros-industrial/motoman_experimental, we've extracted more accurate dimensions. Even if they are 100% perfect, we saw that they improve considerably transformations between links. Now both, data from tf and data from Motoman's controller match much more better, around 2-3mm error, which is less than 50mm of error we had with previous configuration in certain poses.

Find bellow used configuration. Basically we modified dimensions between joints, but we've also modified joint_7_t rotation due to it was inverted.

More details can be found in our motoman fork a167fd1 and 8a64ea1

<joint name="${prefix}joint_1_s" type="revolute">
    <parent link="${parent}"/>
    <child link="${prefix}link_1_s"/>
    <origin xyz="0.100 ${reflect*0.0275} 0.3114" rpy="1.57 0 ${(reflect-1)*1.57}"/>
    <axis xyz="0 0 ${-reflect}" />
    <limit lower="-3.13" upper="3.13" effort="0" velocity="2.95" />
</joint>
<joint name="${prefix}joint_2_l" type="revolute">
    <parent link="${prefix}link_1_s"/>
    <child link="${prefix}link_2_l"/>
    <origin xyz="0 0.0539 -0.2375" rpy="-1.57 0 0"/>
    <axis xyz="0 0 ${-reflect}" />
    <limit lower="-1.90" upper="1.90" effort="0" velocity="2.95" />
</joint>
<joint name="${prefix}joint_3_e" type="revolute">
    <parent link="${prefix}link_2_l"/>
    <child link="${prefix}link_3_e"/>
    <origin xyz="0 0.211 -0.0539" rpy="1.57 0 0"/>
    <axis xyz="0 0 ${-reflect}" />
    <limit lower="-2.95" upper="2.95" effort="0" velocity="2.95" />
</joint>
<joint name="${prefix}joint_4_u" type="revolute">
    <parent link="${prefix}link_3_e"/>
    <child link="${prefix}link_4_u"/>
    <origin xyz="0 -0.0375 -0.149" rpy="-1.57 0 0"/>
    <axis xyz="0 0 ${reflect}" />
    <limit lower="-2.36" upper="2.36" effort="0" velocity="2.95" />
</joint>
<joint name="${prefix}joint_5_r" type="revolute">
    <parent link="${prefix}link_4_u"/>
    <child link="${prefix}link_5_r"/>
    <origin xyz="0 0.233 0.0375" rpy="1.57 0 0"/>
    <axis xyz="0 0 ${reflect}" />
    <limit lower="-3.13" upper="3.13" effort="0" velocity="3.48" />
</joint>
<joint name="${prefix}joint_6_b" type="revolute">
    <parent link="${prefix}link_5_r"/>
    <child link="${prefix}link_6_b"/>
    <origin xyz="0 0.0335 -0.127" rpy="-1.57 0 0"/>
    <axis xyz="0 0 ${reflect}" />
    <limit lower="-1.90" upper="1.90" effort="0" velocity="3.48" />
</joint>
<joint name="${prefix}joint_7_t" type="revolute">
    <parent link="${prefix}link_6_b"/>
    <child link="${prefix}link_7_t"/>
    <origin xyz="0 0.155 -0.0335" rpy="-1.57 0 0"/>
    <axis xyz="0 0 ${-reflect}" />
    <limit lower="-3.13" upper="3.13" effort="0" velocity="6.97" />
</joint>

Apart from that stl files should be updated to match those dimensions.

In any case, it would be very helpful for us to be able to retrieve DH parameters described in #256

gavanderhoorn commented 5 years ago

Thanks for the info @asierfernandez, but a PR that updates the package would be a bit more expedient to get the fix in.