View Categories

OpenManipulator-X-Chap2-規格

C2. Specification 規格 #

C2.1. 硬體規格 #

名稱 單位 OpenManipulator-X 機器手臂
智能馬達 - XM430-W350-T
輸入電壓 V 12
DOF 自由度 - 5 (4 DOF + 1 DOF Gripper)
負載 g 500
重複度 mm < 0.2
速度(Joint) RPM 46
重量 kg 0.70
Reach
伸長範圍
mm 380
Gripper Stroke
爪手張開距離
mm 20 - 75
通訊 - TTL (Level Multidrop BUS)
軟體 - ROS, DYNAMIXEL SDK, Arduino, Processing
主控制器 - PC, OpenCR

C2.2. 大小 #

OpenManipulator Chain spec side

C2.3. Inertia 慣性 #

manipulator x inertia
Total Mass : 711.37 gram

C2.3.1. Joint 1 關節1 #

manipulator x inertia joint1
  • Mass [gram] : 1.0483260e+02
  • Center of Gravity [mm]
    • X : 0.0000000e+00
    • Y : -5.6914372e-01
    • Z : 2.6565513e+01
  • Inertia Tensor with respect to C1 coordinate frame: [GRAM * MM^2]
    • Ixx Ixy Ixz : 1.0781918e+05 0.0000000e+00 0.0000000e+00
    • Iyx Iyy Iyz : 0.0000000e+00 1.0355255e+05 1.8062416e+03
    • Izx Izy Izz : 0.0000000e+00 1.8062416e+03 1.7644210e+04
  • Inertia Tensor at CENTER OF GRAVITY with respect to coordinate frame: [GRAM * MM^2]
    • Ixx Ixy Ixz : 3.3802078e+04 0.0000000e+00 0.0000000e+00
    • Iyx Iyy Iyz : 0.0000000e+00 2.9569411e+04 2.2121514e+02
    • Izx Izy Izz : 0.0000000e+00 2.2121514e+02 1.7610252e+04
  • Principal Moments of Inertia: [GRAM * MM^2]
    • I1 : 1.7606162e+04
    • I2 : 2.9573501e+04
    • I3 : 3.3802078e+04

C2.3.2. Joint 2 關節2 #

manipulator x inertia joint2
  • Mass [gram] : 1.4234630e+02
  • Center of Gravity [mm]
    • X : -9.1617228e+00
    • Y : -4.1915210e-01
    • Z : 1.0599936e+02
  • Inertia Tensor with respect to C2 coordinate frame: [GRAM * MM^2]
    • Ixx Ixy Ixz : 1.8365231e+06 -8.2177190e+02 1.6490470e+05
    • Iyx Iyy Iyz : -8.2177190e+02 1.8562153e+06 7.6370887e+03
    • Izx Izy Izz : 1.6490470e+05 7.6370887e+03 5.4940213e+04
  • Inertia Tensor at CENTER OF GRAVITY with respect to coordinate frame: [GRAM * MM^2]
    • Ixx Ixy Ixz : 2.3711450e+05 -2.7513999e+02 2.6666982e+04
    • Iyx Iyy Iyz : -2.7513999e+02 2.4488355e+05 1.3126636e+03
    • Izx Izy Izz : 2.6666982e+04 1.3126636e+03 4.2967059e+04
  • Principal Moments of Inertia: [GRAM * MM^2]
    • I1 : 3.9362142e+04
    • I2 : 2.4070845e+05
    • I3 : 2.4489452e+05

C2.3.3. Joint 3 關節3 #

manipulator x inertia joint3
  • Mass [gram] : 1.3467049e+02
  • Center of Gravity [mm]
    • X : 3.6312773e-04
    • Y : -4.4304274e-01
    • Z : 9.3290225e+01
  • Inertia Tensor with respect to C3 coordinate frame: [GRAM * MM^2]
    • Ixx Ixy Ixz : 1.3589608e+06 0.0000000e+00 -2.7331036e+00
    • Iyx Iyy Iyz : 0.0000000e+00 1.3502276e+06 6.7882502e+03
    • Izx Izy Izz : -2.7331036e+00 6.7882502e+03 2.4835638e+04
  • Inertia Tensor at CENTER OF GRAVITY with respect to coordinate frame: [GRAM * MM^2]
    • Ixx Ixy Ixz : 1.8688812e+05 0.0000000e+00 1.8290300e+00
    • Iyx Iyy Iyz : 0.0000000e+00 1.7818139e+05 1.2221090e+03
    • Izx Izy Izz : 1.8290300e+00 1.2221090e+03 2.4809204e+04
  • Principal Moments of Inertia: [GRAM * MM^2]
    • I1 : 2.4799466e+04
    • I2 : 1.7819113e+05
    • I3 : 1.8688812e+05

C2.3.4. Joint 4 關節4 #

manipulator x inertia joint4
  • Mass [gram] : 2.3550927e+02
  • Center of Gravity [mm]
    • X : 6.1273313e+00
    • Y : 7.9503949e-04
    • Z : 6.0472935e+01
  • Inertia Tensor with respect to C4 coordinate frame: [GRAM * MM^2]
    • Ixx Ixy Ixz : 1.1283350e+06 2.2172215e+02 -6.4649200e+04
    • Iyx Iyy Iyz : 2.2172215e+02 1.0777914e+06 3.9825896e+00
    • Izx Izy Izz : -6.4649200e+04 3.9825896e+00 1.8277436e+05
  • Inertia Tensor at CENTER OF GRAVITY with respect to coordinate frame: [GRAM * MM^2]
    • Ixx Ixy Ixz : 2.6708326e+05 2.2286943e+02 2.2615865e+04
    • Iyx Iyy Iyz : 2.2286943e+02 2.0769766e+05 1.5305492e+01
    • Izx Izy Izz : 2.2615865e+04 1.5305492e+01 1.7393236e+05
  • Principal Moments of Inertia: [GRAM * MM^2]
    • I1 : 1.6873182e+05
    • I2 : 2.0769694e+05
    • I3 : 2.7228452e+05

C2.4. 了解 URDF 通用機器人描述格式 #

了解 OpenManipulator-X 機器手臂的 URDF (Universal Robot Description Format 通用機器人描述格式)。

C2.4.1. 什麼是 URDF? #

URDF(Universal Robot Description Format 通用機器人描述格式),是一種基於 XML 的格式,用於描述機器人的物理結構、運動學(kinematics)、動力學(dynamics),和視覺化屬性。它廣泛用於 ROS (Robot Operating System 機器人作業系統)中,來定義用於模擬、運動規劃(motion planning)和視覺化的機器人模型。

URDF 使用以下關鍵元素來定義機器人:

  • Links:定義機器人的視覺表示、碰撞幾何和慣性特性。
  • Joints:定義 Links 之間的連接和運動限制(constraints)。
  • Visuals:描述機器人在視覺化工具中的呈現方式。
  • Collisions:定義用於基於物理的交互作用的簡化幾何圖形。
  • Inertial properties:指定物理模擬的質量(mass)、重心(center of gravity)和慣性張量(inertia tensor)。

為了更詳細地了解 URDF,我們建議參考 ROS2 Wiki 上的 URDF Tutorial。要理解和學習 URDF 的最好方法,是自己建立一個簡單的機器人。

C2.4.2. 視覺化 OpenManipulator-X 的 URDF 結構 #

在深入研究 URDF 細分之前,了解 OpenManipulator-X 的層次結構(hierarchical structure)至關重要。下面的 URDF 圖,直觀地表示了 Links 和 Joints 之間的父子關係(parent-child relationships)。

URDF 圖的主要特點

  • Root Node 根結點(World)
    • 機器人透過 world_fixed,固定到世界座標系。
  • Link Structure 連桿結構:(代表機器人的剛體)
    • 機器手臂,由五支主 link (link1 至link5)組成,構成整個機器手臂。
    • end-effector 末端執行器(end_effector_link) 連接到 link5。
    • gripper 夾手機構,包括 gripper_left_link 和gripper_right_link。
  • Joint Connections 關節連結:(定義每個 Link,相對於另一個 Link 的移動方式)
    • 每個 Link ,透過旋轉形關節(joint1 至 joint4),或棱柱形關節(gripper_left_joint、gripper_right_joint)來彼此連接。
    • gripper 夾手,透過mimic 模擬關節(gripper_right_joint_mimic)進行操作,確保兩根手指可對稱的移動。

下圖顯示了 RViz 中,可視化的 OpenManipulator-X URDF 模型。它包括 joint 關節位置,和 link 尺寸,清晰地表示出機器手臂的結構。

rviz om view

C2.4.3. URDF 與 Xacro #

所提供的 URDF,使用 Xacro (XML macros 巨集),來簡化和模組化機器人描述。 Xacro 允許重複使用組件,並使 URDF 更易於維護。
以下解釋基於 Xacro 檔案:

				
					open_manipulator/open_manipulator_x_description/urdf/open_manipulator_x.urdf.xacro
				
			

在文件的開頭,定義了一個 macro 巨集:

				
					<xacro:macro name="open_manipulator_x" params="prefix=''">
				
			

這允許,結構相同但不同前綴(prefixes),可以重複使用,使其能夠靈活地適應多機器人環境。

C2.4.4. 定義 Link 連桿 #

Link 連桿,代表機器人的剛體。每個 Link 都具有 visual 視覺、collision 碰撞,和 inertial 慣性屬性。

OpenManipulator-X 中的 link1 範例:

				
					<link name="${prefix}link1">
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <mesh filename="${meshes_file_direction}/link1.stl" scale="0.001 0.001 0.001"/>
    </geometry>
    <material name="grey"/>
  </visual>
  
  <collision>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <mesh filename="${meshes_file_direction}/link1.stl" scale="0.001 0.001 0.001"/>
    </geometry>
  </collision>

  <inertial>
    <origin xyz="3.0876154e-04 0.0000000e+00 -1.2176461e-04" />
    <mass value="7.9119962e-02" />
    <inertia ixx="1.2505234e-05" ixy="0.0" ixz="-1.7855208e-07"
             iyy="2.1898364e-05" iyz="0.0"
             izz="1.9267361e-05" />
  </inertial>
</link>
				
			

說明:

  • <visual>:定義 Link 如何使用 3D mesh 網格(link1.stl),在模擬或視覺化工具(例如 RViz)中顯示。
  • <collision>:指定用於基於物理的交互作用(例如 collision 碰撞)的簡化幾何學。
  • <inertial>:定義 mass 質量、center of gravity 重心和 inertia tensor 慣性張量,這些對於真實的物理模擬至關重要。。

C2.4.5. 定義 Joint 關節 #

Joint 關節連接兩個 Link 連桿,並定義它們相對於彼此如何移動。

OpenManipulator-X 中的 joint1 範例:

				
					<joint name="${prefix}joint1" type="revolute">
  <parent link="${prefix}link1"/>
  <child link="${prefix}link2"/>
  <origin xyz="0.012 0.0 0.017" rpy="0 0 0"/>
  <axis xyz="0 0 1"/>
  <limit velocity="4.8" effort="1" lower="${-pi}" upper="${pi}" />
  <dynamics damping="0.1"/>
</joint>
				
			

說明:

  • type=”revolute”:定義旋轉關節(在機器手臂中很常見)。
  • <parent> 和 <child>:指定由 Joint 關節連接的兩個 Link。
  • <origin>:定義相對於 parent 連結的 joint 關節位置。
  • <axis>:指定旋轉軸 (001 表示繞 Z 軸旋轉)。
  • <limit>:定義運動的 constraints 限制(如速度、扭力和範圍)。
  • <dynamics>:包括 damping 阻尼,它會影響關節移動的平穩程度。

C2.4.6. 增加 Prismatic Joint(棱柱形關節) #

Prismatic joints(棱柱形關節),允許 Linear 線性運動,而不是旋轉。

OpenManipulator-XGripper 範例:

				
					<joint name="${prefix}gripper_left_joint" type="prismatic">
  <parent link="${prefix}link5"/>
  <child link="${prefix}gripper_left_link"/>
  <origin xyz="0.0817 0.021 0.0" rpy="0 0 0"/>
  <axis xyz="0 1 0"/>
  <limit velocity="4.8" effort="1" lower="-0.010" upper="0.019" />
  <dynamics damping="0.1"/>
</joint>
				
			

說明:

  • type=”prismatic”:允許沿著定義的軸,進行線性移動。
  • <limit>:限制移動範圍(從 -0.010 公尺至 0.019 公尺)。
  • Used for:gripper 夾手的運動(opening 和 closing)。

C2.4.7. 使用 Fixed Joint(固定關節) #

當一個 Link 相對於另一個 Link 不移動時,可使用 Fixed Joint。

範例:

				
					<joint name="${prefix}end_effector_joint" type="fixed">
  <parent link="${prefix}link5"/>
  <child link="${prefix}end_effector_link"/>
  <origin xyz="0.126 0.0 0.0" rpy="0 0 0"/>
</joint>
				
			

說明:

  • type=”fixed”:Link 之間沒有相對移動。
  • Used for:end-effector 末端執行器,或不動的組件。