Denavit-Hartenberg (DH) to URDF/SDF or /tf /tf2?
Hi! Can anybody advise, is there any package to build a manipulator using Dehavit-Hartenberg parameters, then convert to URDF/SDF or just use outputs as /tf /tf2 ?
Asked by MaximN74 on 2018-08-16 23:23:25 UTC
Answers
I haven't used it myself, but AdoHaha/DH2URDF claims to be able to do this.
Asked by gvdhoorn on 2018-08-17 02:06:47 UTC
Comments
Is it useful and can it convert URDF to DH?
Asked by itfanr on 2018-09-09 22:35:24 UTC
I don't know. The original question poster never replied.
Asked by gvdhoorn on 2018-09-10 01:19:58 UTC
Hi, I just wrote a small utility for converting GraspIt hand models (which use DH parameters) to a URDF: https://github.com/samarth-robo/GraspIt2URDF.
Asked by samarth.robo on 2018-12-18 21:10:53 UTC
Comments
Hi! Thanks for your reply. I'll try your package and inform you. Tnanks again!
Asked by MaximN74 on 2018-12-19 02:05:37 UTC
The following example shows how to define a revolute DoF defined using the Denavit-Hartenberg parameters (theta, d, a and alpha) using URDF in a systematic way.
<link name="base_link">...</link>
<link name="tmp_11">...</link>
<joint name="theta1" type="revolute">
<parent link="base_link"/>
<child link="tmp_11"/>
<axis xyz="0 0 1"/>
<limit effort="1000.0" lower="-3.1415" upper="3.1415" velocity="0.5"/>
<origin rpy="0 0 {{ value_theta1 }}" xyz="0 0 0"/>
</joint>
<link name="tmp_12">...</link>
<joint name="d1" type="fixed">
<parent link="tmp_11"/>
<child link="tmp_12"/>
<origin rpy="0 0 0" xyz="0 0 {{ value_d1 }}"/>
</joint>
<link name="tmp_13">...</link>
<joint name="a1" type="fixed">
<parent link="tmp_12"/>
<child link="tmp_13"/>
<origin rpy="0 0 0" xyz="{{ value_a1 }} 0 0"/>
</joint>
<link name="L1">...</link>
<joint name="alpha1" type="fixed">
<parent link="tmp_13"/>
<child link="L1"/>
<origin rpy="{{ value_alpha1 }} 0 0" xyz="0 0 0"/>
</joint>
Asked by narcispr on 2020-09-01 05:59:38 UTC
Comments