-
Notifications
You must be signed in to change notification settings - Fork 196
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
sda10f: dimensions in URDF does not match specifications #232
Comments
This package was introduced by @thiagodefreitas in 45bd327. According to the package manifest added in that commit, the reference is/was: 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. |
@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. |
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. 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 |
I've just posted an enhancement request/proposal that could make checking these sort of things easier/feasible: #238. |
None of the dimensions match except for
Also as @EricMarcil wrote:
Maybe this was the confusion, since the distance between both L axes is in fact 505mm as per tf data. @gavanderhoorn wrote:
This would be interesting. |
@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 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: 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. |
I tested the URDF from moveit_experimental repo as well.
With this change, the values match with that of datasheet. |
We've been also working around this issue with sda10f robot. The model described motoman_sda10f_support is far away from official sda10f model. 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 |
Thanks for the info @asierfernandez, but a PR that updates the package would be a bit more expedient to get the fix in. |
While working on ros-industrial/ros_industrial_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
shows
i.e. 506mm. Similarly, arm_right_link_4_u and arm_right_link_2_l have an offset of 360mm
shows
i.e. 350mm
This seems to be the case with other dimensions as well. What is the reference used for the URDF?
The text was updated successfully, but these errors were encountered: