Files
hivecore_robot_motion/urdf/robot.urdf
2025-10-16 09:06:38 +08:00

488 lines
13 KiB
XML

<?xml version="1.0"?>
<robot name="dual_arm_leg_robot">
<!-- 基础底座 -->
<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.3 0.3 0.1"/>
</geometry>
<material name="gray">
<color rgba="0.5 0.5 0.5 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.3 0.3 0.1"/>
</geometry>
</collision>
</link>
<!-- 左手 (6自由度) -->
<!-- 肩关节1 - 旋转 -->
<joint name="left_arm_joint1" type="revolute">
<parent link="base_link"/>
<child link="left_arm_link1"/>
<origin xyz="0.1 0.15 0.05" rpy="0 0 0"/>
<limit lower="-1.57" upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="left_arm_link1">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
</collision>
</link>
<!-- 肩关节2 -->
<joint name="left_arm_joint2" type="revolute">
<parent link="left_arm_link1"/>
<child link="left_arm_link2"/>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<limit lower="-1.57" upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 1 0"/>
</joint>
<link name="left_arm_link2">
<visual>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.02"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.02"/>
</geometry>
</collision>
</link>
<!-- 肘关节 -->
<joint name="left_arm_joint3" type="revolute">
<parent link="left_arm_link2"/>
<child link="left_arm_link3"/>
<origin xyz="0 0 0.3" rpy="0 0 0"/>
<limit lower="-1.57" upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 1 0"/>
</joint>
<link name="left_arm_link3">
<visual>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.02"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.02"/>
</geometry>
</collision>
</link>
<!-- 腕关节1 -->
<joint name="left_arm_joint4" type="revolute">
<parent link="left_arm_link3"/>
<child link="left_arm_link4"/>
<origin xyz="0 0 0.3" rpy="0 0 0"/>
<limit lower="-1.57" upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="left_arm_link4">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
</collision>
</link>
<!-- 腕关节2 -->
<joint name="left_arm_joint5" type="revolute">
<parent link="left_arm_link4"/>
<child link="left_arm_link5"/>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<limit lower="-1.57" upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 1 0"/>
</joint>
<link name="left_arm_link5">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
</collision>
</link>
<!-- 腕关节3 -->
<joint name="left_arm_joint6" type="revolute">
<parent link="left_arm_link5"/>
<child link="left_arm_end_effector"/>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<limit lower="-3.14" upper="3.14" effort="100" velocity="1.0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="left_arm_end_effector">
<visual>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="cyan">
<color rgba="0 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
</link>
<!-- 右手 (6自由度) -->
<!-- 肩关节1 - 旋转 -->
<joint name="right_arm_joint1" type="revolute">
<parent link="base_link"/>
<child link="right_arm_link1"/>
<origin xyz="0.1 -0.15 0.05" rpy="0 0 0"/>
<limit lower="-1.57" upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="right_arm_link1">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
</collision>
</link>
<!-- 肩关节2 -->
<joint name="right_arm_joint2" type="revolute">
<parent link="right_arm_link1"/>
<child link="right_arm_link2"/>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<limit lower="-1.57" upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 1 0"/>
</joint>
<link name="right_arm_link2">
<visual>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.02"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.02"/>
</geometry>
</collision>
</link>
<!-- 肘关节 -->
<joint name="right_arm_joint3" type="revolute">
<parent link="right_arm_link2"/>
<child link="right_arm_link3"/>
<origin xyz="0 0 0.3" rpy="0 0 0"/>
<limit lower="-1.57" upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 1 0"/>
</joint>
<link name="right_arm_link3">
<visual>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.02"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.02"/>
</geometry>
</collision>
</link>
<!-- 腕关节1 -->
<joint name="right_arm_joint4" type="revolute">
<parent link="right_arm_link3"/>
<child link="right_arm_link4"/>
<origin xyz="0 0 0.3" rpy="0 0 0"/>
<limit lower="-1.57" upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="right_arm_link4">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
</collision>
</link>
<!-- 腕关节2 -->
<joint name="right_arm_joint5" type="revolute">
<parent link="right_arm_link4"/>
<child link="right_arm_link5"/>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<limit lower="-1.57" upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 1 0"/>
</joint>
<link name="right_arm_link5">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.02"/>
</geometry>
</collision>
</link>
<!-- 腕关节3 -->
<joint name="right_arm_joint6" type="revolute">
<parent link="right_arm_link5"/>
<child link="right_arm_end_effector"/>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<limit lower="-3.14" upper="3.14" effort="100" velocity="1.0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="right_arm_end_effector">
<visual>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="magenta">
<color rgba="1 0 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
</link>
<!-- 左腿 (3自由度) -->
<!-- 髋关节1 -->
<joint name="left_leg_joint1" type="revolute">
<parent link="base_link"/>
<child link="left_leg_link1"/>
<origin xyz="-0.1 0.1 0" rpy="0 0 0"/>
<limit lower="-0.785" upper="0.785" effort="100" velocity="1.0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="left_leg_link1">
<visual>
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.025"/>
</geometry>
<material name="green">
<color rgba="0 1 0 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.025"/>
</geometry>
</collision>
</link>
<!-- 膝关节 -->
<joint name="left_leg_joint2" type="revolute">
<parent link="left_leg_link1"/>
<child link="left_leg_link2"/>
<origin xyz="0 0 -0.3" rpy="0 0 0"/>
<limit lower=0 upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 1 0"/>
</joint>
<link name="left_leg_link2">
<visual>
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.025"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.025"/>
</geometry>
</collision>
</link>
<!-- 踝关节 -->
<joint name="left_leg_joint3" type="revolute">
<parent link="left_leg_link2"/>
<child link="left_foot"/>
<origin xyz="0 0 -0.3" rpy="0 0 0"/>
<limit lower="-0.52" upper="0.52" effort="100" velocity="1.0"/>
<axis xyz="0 1 0"/>
</joint>
<link name="left_foot">
<visual>
<origin xyz="0 0 -0.05" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.08 0.03"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin xyz="0 0 -0.05" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.08 0.03"/>
</geometry>
</collision>
</link>
<!-- 右腿 (3自由度) -->
<!-- 髋关节1 -->
<joint name="right_leg_joint1" type="revolute">
<parent link="base_link"/>
<child link="right_leg_link1"/>
<origin xyz="-0.1 -0.1 0" rpy="0 0 0"/>
<limit lower="-0.785" upper="0.785" effort="100" velocity="1.0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="right_leg_link1">
<visual>
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.025"/>
</geometry>
<material name="yellow">
<color rgba="1 1 0 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.025"/>
</geometry>
</collision>
</link>
<!-- 膝关节 -->
<joint name="right_leg_joint2" type="revolute">
<parent link="right_leg_link1"/>
<child link="right_leg_link2"/>
<origin xyz="0 0 -0.3" rpy="0 0 0"/>
<limit lower=0 upper="1.57" effort="100" velocity="1.0"/>
<axis xyz="0 1 0"/>
</joint>
<link name="right_leg_link2">
<visual>
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.025"/>
</geometry>
<material name="yellow"/>
</visual>
<collision>
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
<geometry>
<cylinder length="0.3" radius="0.025"/>
</geometry>
</collision>
</link>
<!-- 踝关节 -->
<joint name="right_leg_joint3" type="revolute">
<parent link="right_leg_link2"/>
<child link="right_foot"/>
<origin xyz="0 0 -0.3" rpy="0 0 0"/>
<limit lower="-0.52" upper="0.52" effort="100" velocity="1.0"/>
<axis xyz="0 1 0"/>
</joint>
<link name="right_foot">
<visual>
<origin xyz="0 0 -0.05" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.08 0.03"/>
</geometry>
<material name="yellow"/>
</visual>
<collision>
<origin xyz="0 0 -0.05" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.08 0.03"/>
</geometry>
</collision>
</link>
</robot>