6.1. 啟動 Controller

在啟動 controller 控制器套件之前,請檢查 open_manipulator_controller 套件中的open_manipulator_controller 啟動檔。

 <launch>
    <arg name="use_robot_name"         default="open_manipulator"/>

    <arg name="dynamixel_usb_port"     default="/dev/ttyUSB0"/>
    <arg name="dynamixel_baud_rate"    default="1000000"/>

    <arg name="control_period"         default="0.010"/>

    <arg name="use_platform"           default="true"/>

    <arg name="use_moveit"             default="false"/>
    <arg name="planning_group_name"    default="arm"/>
    <arg name="moveit_sample_duration" default="0.050"/>

    <group if="$(arg use_moveit)">
      <include file="$(find open_manipulator_controller)/launch/open_manipulator_moveit.launch">
        <arg name="robot_name"      value="$(arg use_robot_name)"/>
        <arg name="sample_duration" value="$(arg moveit_sample_duration)"/>
      </include>
    </group>

    <node name="$(arg use_robot_name)" pkg="open_manipulator_controller" type="open_manipulator_controller" output="screen" args="$(arg dynamixel_usb_port) $(arg dynamixel_baud_rate)">
        <param name="using_platform"       value="$(arg use_platform)"/>
        <param name="using_moveit"         value="$(arg use_moveit)"/>
        <param name="planning_group_name"  value="$(arg planning_group_name)"/>
        <param name="control_period"       value="$(arg control_period)"/>
        <param name="moveit_sample_duration"  value="$(arg moveit_sample_duration)"/>
    </node>

  </launch>

Parameters 參數列表:以下參數可設置控制環境。

  • use_robot_name

    • 是一個設置機器手臂名稱的參數(ROS messages 的 namespace)。

  • dynamixel_usb_port

    • 是一個參數,用於設置 USB 端口,以連接 OpenMANIPULATOR-X 手臂的DYNAMIXEL 智能馬達。如果使用 U2D2 轉接器,則應設置為 /dev/ttyUSB@。如果是使用 OpenCR 控制板,則應設置 /dev/ttyACM@(@ 表示連接到 DYNAMIXEL 智能馬達的端口 port number)。

  • dynamixel_baud_rate

    • 是一個設置 DYNAMIXEL 智能馬達 baud rate 的參數。機器手臂 OpenMANIPULATOR-X 中使用的 DYNAMIXEL 智能馬達的預設 baud rate 是1,000,000。

  • control_period

    • 是用於設置 DYNAMIXEL 智能馬達和 PC 之間的通訊週期的參數(控制循 loop time)。

  • use_platform

    • 是一個參數,用於設置是否使用實體的 OpenMANIPULATOR-X 手臂或是使用模擬的 OpenMANIPULATOR-X 手臂。請參考 ROS Simulation 模擬章節。

  • use_moveit,planning_group_name,及 moveit_sample_duration

設定好參數後,啟動 OpenMANIPULATOR-X controller 控制器來開始 [ROS] 操作

請新開 terminal 視窗, 執行 roscore 指令

$ roscore

運行 roscore 後,打開另一個 terminal 視窗,然後在視窗中執行以下指令。

$ roslaunch open_manipulator_controller open_manipulator_controller.launch

警示:請在運行 OpenMANIPULATOR-X 手臂之前,先檢查每個關節的位置。如果關節位置超出運作範圍,手臂可能會停止操作。下面的圖片向您展示了 OpenMANIPULATOR-X 機器手臂的理想姿勢方位。當未啟用 DYNAMIXEL 智能馬達的扭力時,請調整每個關節的方位如下圖所示。

成功完成流程後,terminal 視窗將顯示以下消息。

SUMMARY
========

PARAMETERS
 * /open_manipulator/control_period: 0.01
 * /open_manipulator/moveit_sample_duration: 0.05
 * /open_manipulator/planning_group_name: arm
 * /open_manipulator/using_moveit: False
 * /open_manipulator/using_platform: True
 * /rosdistro: kinetic
 * /rosversion: 1.12.14

NODES
  /
    open_manipulator (open_manipulator_controller/open_manipulator_controller)

ROS_MASTER_URI=http://localhost:11311

process[open_manipulator-1]: started with pid [23452]
Joint Dynamixel ID : 11, Model Name : XM430-W350
Joint Dynamixel ID : 12, Model Name : XM430-W350
Joint Dynamixel ID : 13, Model Name : XM430-W350
Joint Dynamixel ID : 14, Model Name : XM430-W350
Gripper Dynamixel ID : 15, Model Name :XM430-W350
[ INFO] [1544509070.096942788]: Succeeded to init /open_manipulator

TIP:

  • 如果無法加載 DYNAMIXEL 智能馬達,請使用 DYNAMIXEL-Workbench 套件中的以下指令來檢查 DYNAMIXEL 的設定。

    • rosrun dynamixel_workbench_controllers find_dynamixel /dev/ ttyUSB0

    • 如果你找不到任何 DYNAMIXEL,請使用 ROBOTIS 的下列軟體,來檢查 DYNAMIXEL 馬達的韌體狀況(R+ Manager 2.0 或 DYNAMIXEL Wizard 2.0)

  • 如果您想更改 Dynamixel 馬達的 ID,請檢查 open_manipulator_lib 資料夾中的 open_manipulator.cpp。 關節的預設 ID 為 11,12,13,14,夾手的預設 ID 為15。

備註:OpenMANIPULATOR-X controller 與 Protocol 2.0 相容。Protocol 1.0 不支持同時存取多個 DYNAMIXEL 的 SyncRead 指令。Protocol 2.0 支持 Dynamixel MX 2.0,X 系列和 Pro 系列智能馬達,但它不支持 Dynamixel AX,RX 和 EX 系列智能馬達。

Last updated