update urdf and dependencies

This commit is contained in:
2026-03-09 20:39:02 +01:00
parent c753c369b4
commit 15da0ef2fd
11 changed files with 204 additions and 57 deletions

View File

@@ -36,9 +36,9 @@
<link name="arm">
<inertial>
<origin xyz="0.00005 0.0065 0.00563" rpy="0 0 0"/>
<mass value="0.150"/>
<inertia ixx="4.05e-05" iyy="1.17e-05" izz="3.66e-05"
ixy="0.0" iyz="1.08e-07" ixz="0.0"/>
<mass value="0.010"/>
<inertia ixx="2.70e-06" iyy="7.80e-07" izz="2.44e-06"
ixy="0.0" iyz="7.20e-08" ixz="0.0"/>
</inertial>
<visual>
<origin xyz="0.006947 -0.00395 -0.14796" rpy="0 0 0"/>
@@ -73,7 +73,7 @@
Tip at (0.07, -0.07, 0) → 45° diagonal in +X/-Y.
CoM = (5×0.035+10×0.07)/15 = 0.0583 along both +X and -Y.
Inertia tensor rotated 45° to match diagonal rod axis. -->
<origin xyz="0.0583 -0.0583 0.0" rpy="0 0 0"/>
<origin xyz="0.1583 -0.0983 -0.0" rpy="0 0 0"/>
<mass value="0.015"/>
<inertia ixx="6.16e-06" iyy="6.16e-06" izz="1.23e-05"
ixy="6.10e-06" iyz="0.0" ixz="0.0"/>
@@ -93,13 +93,14 @@
</link>
<!-- Pendulum joint: arm → pendulum, bearing axis along Y.
Joint origin corrected from mesh analysis (Fusion2URDF was 180mm off). -->
Joint origin corrected from mesh analysis (Fusion2URDF was 180mm off).
rpy pitch +90° so qpos=0 = pendulum hanging down (gravity-stable). -->
<joint name="pendulum_joint" type="continuous">
<origin xyz="0.000052 0.019274 0.014993" rpy="0 0 0"/>
<origin xyz="0.000052 0.019274 0.014993" rpy="0 1.5708 0"/>
<parent link="arm"/>
<child link="pendulum"/>
<axis xyz="0 -1 0"/>
<dynamics damping="0.0005"/>
<dynamics damping="0.0001"/>
</joint>
</robot>