openarm_ros2/openarm_two_arms/urdf/openarm_two_arms.urdf.xacro

26 lines
945 B
Plaintext
Raw Normal View History

<?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_two_arms">
<link name="world"/>
2025-03-10 08:06:07 +00:00
<xacro:include filename="openarm.xacro"/>
<xacro:include filename="openarm_two_arms_pedestal.urdf"/>
2025-03-10 08:16:37 +00:00
<xacro:openarm prefix="right_" side="right"/>
2025-03-10 09:08:07 +00:00
<xacro:openarm prefix="left_" side="left"/>
<joint name="dummy_joint" type="fixed">
<parent link="world"/>
<child link="pedestal_link"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
2025-03-10 14:13:04 +00:00
<joint name="right_fixed1" type="fixed">
<parent link="pedestal_link"/>
2025-03-10 14:13:04 +00:00
<child link="left_link1"/>
<origin rpy="3.0144791747751833 -1.5707963267948324 0.12689401604101067" xyz="0.09 0.0 0.893"/>
</joint>
2025-03-10 14:13:04 +00:00
<joint name="left_fixed1" type="fixed">
<parent link="pedestal_link"/>
2025-03-10 14:13:04 +00:00
<child link="right_link1"/>
2025-03-10 12:24:14 +00:00
<origin rpy="${3.0186531925068127 + pi} -1.5707963267948268 0.12293946108298068" xyz="-0.09 0.0 0.893"/>
</joint>
</robot>