ROS 入門向けマニピュレータ導入検証

著者:yamamoto.yosuke

ROS 入門向けマニピュレータ導入検証

ROS やその MoveIt の学習を始めたい,もしくは Gazebo などのシミュレータでの実行はできたので,実際のロボットも動かしてみたい!と思っている方もいらっしゃるのではないでしょうか.

また,Ubuntu ROS をインストールする PC はどのようなものにしたら良いのか?というご質問と同じように,マニピュレータを ROS で動かす学習をしたいが実際にどのようなロボットを導入したら良いのか?といったご質問を TORK にいただくことがあります.

そこで,価格なども含めて比較的入手性の良さそうな次の2種のマニピュレーションロボットを購入して ROS や MoveIt で利用した場合について調査・検証しました.

  • uArm Swift Pro
  • Open Manipulator X
uArm Swift Pro Open Manipulator X
販売価格 ¥99,000.- ¥272,800.-
納期 数日 2〜7週間
腕部自由度 3 DOF 4 DOF
PC 接続 micro USB-B micro USB-B
外観

 

各マニピュレータ ROS 対応情報

uArm Swift Pro

Open Manipulator X

ROS での導入方法

uArm Swift Pro

GitHub ページ SwiftAndProForROS https://github.com/uArm-Developer/RosForSwiftAndSwiftPro のトップページにある README.md に従ってダウンロードとインストールを行いました.

まず前提としてロボットに接続する側の PC に  Ubuntu と ROS がインストールされている必要があります.ROS のインストールは下記サイトを参考に行うことができます.

README.md にはおおまかにしか書いていないように思えたので,補足的に書き加えると次のようになります.

$ sudo apt-get install git ros-kinetic-serial
$ mkdir -p ~/catkin_ws/src  #既にワークスペースがあるならそちらを使ってもOK
$ cd ~/catkin_ws/src
$ catkin_init_workspace
$ git clone https://github.com/uArm-Developer/RosForSwiftAndSwiftPro.git
$ cd ~/catkin_ws
$ rosdep install --from-paths src --ignore-src -r -y
$ catkin_make
$ source ~/catkin_ws/devel/setup.bash

ここでは Ubuntu 16.04 + ROS kinetic のケースを書いていますが Ubuntu 18.04 + ROS melodic でも下記の kinetic のところを melodic にしてインストール・実行できました.

「 2. Set up enviroment 」は手順通りに ROS 環境がターミナルに反映されるための設定を行いました.ROS melodic の場合もインストールに関するコマンドの kinetic を melodic に変更することでインストールでき,今回の記事の範囲の動作を確認しました.

Open Manipulator X

<2022年8月31日追記>
本記事公開後に OpenManipulator-X のソフトウェア構成の変更があり,本記事で紹介した手順のアップデートが必要でしたので更新内容を新しい記事「“ROS 入門向けマニピュレータ導入検証” ROS Melodic & Noetic 対応更新」にて紹介しています.

eマニュアルが充実しているので下記 URL の手順に沿ってインストール作業を進めました.

こちらも ROS melodic の場合もインストールに関するコマンドの kinetic を melodic に変更することでインストールでき,今回の記事の範囲の動作を確認しています.

eマニュアルの手順に従い,Arduino IDE でポートの設定なども行いました.

MoveIt GUI でのマニピュレーション操作

uArm Swift Pro と Open Manipulator X を ROS の MoveIt の GUI(グラフィカル・ユーザ・インタフェース)から動かした手順を中心に報告します.

uArm Swift Pro

まずは uArm Swift Pro の電源投入と PC との接続を行います.

  1. uArm Swift Pro に ACアダプター電源を接続して電源を入れる
  2. USB ケーブルで uArm Swift Pro と Ubuntu PC を接続する

次にターミナルを2つ開いて,1つ目のターミナルでは uArm Swift Pro への接続と制御を実行します.

ターミナル1

$ sudo chmod 666 /dev/ttyACM0
$ roslaunch swiftpro pro_control.launch

2つ目のターミナルでは MoveIt を実行します.

ターミナル2

$ roslaunch pro_moveit_config demo.launch

腕自由度が 3 自由度しかないため MoveIt 上の空間の 6 自由度(XYZ, RPY)でインタラクティブマーカを動かそうとすると上手く動かせません.”Allow Approx IK Solutions” のチェックを入れるとロボットの自由度・可動範囲内でインタラクティブマーカの厳密ではないものの最適解が計算されるので比較的楽にインタラクティブマーカを動かすことができます.

  • Allow Approx IK Solutions のチェックを入れる

インタラクティブマーカを動かして目標姿勢を定めてから [ Plan and Execute ] ボタンを押します.

必須ではないですが MoveIt の表示上調整すると良かった項目を挙げます.

  • Displays → MotionPlanning
    • Planning Request → Interactive Marker Size : 0.1
    • Planned Path → Loop Animation : オフ

問題もありました.MoveIt に表示される uArm Swift Pro のロボットモデルがパラレルリンク分の運動学計算がされていないような状態と正常に計算されたような状態を交互に繰り返していました.この件は GitHub Issue – Missing robot joints としても報告されているようですが改善はされていないようです.

MoveIt やコントローラを終了するには各ターミナルで Ctrl+C を入力することで終了します.

uArm Swift Pro は動作時の剛性感が高いように思いました.ステッピングモータでガッチリと固定されているような印象を受けました.ただ MoveIt から制御した動作はカタカタカタとしていました.これはロボット側のファームウェアを更新したらカタカタの度合いが少し細かくなりましたがまだ残っています.uArm Swift Pro を uArm Studio から動かすと動きがスムーズだったので ROS や MoveIt と uArm Swift Pro のインタフェース部分に詰めきれていない部分があるように感じました.

Open Manipulator X

<2022年8月31日追記>
本記事公開後に OpenManipulator-X のソフトウェア構成の変更があり,本記事で紹介した手順のアップデートが必要でしたので更新内容を新しい記事「“ROS 入門向けマニピュレータ導入検証” ROS Melodic & Noetic 対応更新」にて紹介しています.

Gazebo Simulation

まずは Gazebo シミュレータが用意されているので Gazebo 上の Open Manipulator X を MoveIt から動かしてみました.

ターミナルを2つ開いて,1つ目のターミナルでは Open Manipulator X の Gazebo シミュレータを起動します.

ターミナル1

$ roslaunch open_manipulator_gazebo open_manipulator_gazebo.launch

正常に実行されると次の画像のような Gazebo のウィンドウが表示されます.ここで一番下段の部分にある ▶ ボタンをクリックしてシミュレータを走らせます.

次にコントローラと MoveIt を起動します.

ターミナル2

$ roslaunch open_manipulator_controller open_manipulator_controller.launch use_moveit:=true use_platform:=false

空間6自由度に対して腕部自由度が4自由度と少ないので Allow Approx IK Solutions のチェックを入れると楽にインタラクティブマーカを動かすことができます.

インタラクティブマーカを動かして目標姿勢を定めてから [ Plan and Execute ] ボタンを押します.

実機動作

次に Open Manipulator X の実機ロボットを MoveIt GUI から動かしてみました.

今回は Ubuntu PC と Open Manipulator X を OpenCR 回路を経由して接続しました.接続方法は下記ページに説明があります.

http://emanual.robotis.com/docs/en/platform/openmanipulator_x/ros_setup/#opencr

  1. Open Manipulator X から出ているケーブルを OpenCR ボードに差し込む
  2. AC アダプタからの直流電源を OpenCR ボードに接続
  3. USB ケーブルで Ubuntu PC と OpenCR ボードを接続
  4. OpenCR ボードの電源を入れる

ターミナルを1つ開いてコントローラと MoveIt を起動します.

ターミナル1

$ roslaunch open_manipulator_controller open_manipulator_controller.launch dynamixel_usb_port:=/dev/ttyACM0 use_moveit:=true

Gazebo シミュレーションのときと同様に “Allow Approx IK Solutions” のチェックを入れます.

インタラクティブマーカを動かして目標姿勢を定めてから [ Plan and Execute ] ボタンを押すと,Gazebo シミュレータで行ったときと同じように実機ロボットを操作できました.

MoveIt Commander でのマニピュレーション動作

MoveIt の GUI 経由で uArm Swift Pro と Open Manipulator X を操作することができました.次の段階としてプログラムから MoveIt を操作してロボットを動かしてみました.

GUI からではなくプログラムからロボットを操作できることで,例えば画像処理から得られた座標をもとににマニピュレータを動かすといった応用につながります.

プログラムから MoveIt を動かすには MoveIt Commander を利用します.MoveIt Commander には C++ や Python のインタフェースが用意されていますので,今回は Python にてプログラムを作成して各ロボットを動作させました.

uArm Swift Pro

MoveIt の GUI にあった “Allow Approx IK Solutions” にチェックを入れた場合と同様の動作指令を出せる MoveIt Commander の機能が set_joint_value_target() メソッドです.一般的には set_joint_value_target() メソッドには各関節の目標角度を引数として渡すことがまず説明されるかと思いますが,第1引数に Pose 型か PoseStamped 型のデータを第2引数に True (=近似解=Approximate / デフォルトは False =厳密解)を渡すことでマニピュレータの自由度が少ないことにより厳密解が得られない状態を近似解を用いることで回避します.

なお,6自由度以上を有するマニピュレータでは一般的に set_pose_target() に Pose 型か PoseStamped 型のデータを渡して厳密解をもって動作させますので,そのようなマニピュレータのプログラムを応用する場合には注意が必要です.

今回作成したテストプログラムを以下に記します.

uArm Swift Pro – MoveIt Commander テストプログラム

#!/usr/bin/env python

import sys, math, copy
import rospy, tf, geometry_msgs.msg

from moveit_commander import MoveGroupCommander, RobotCommander
from geometry_msgs.msg import Pose, PoseStamped

if __name__ == '__main__':
    
    node_name = "commander_example"
    rospy.init_node( node_name, anonymous=True )
    
    group = MoveGroupCommander("arm")
    
    group.set_planning_time( 600.0 )
    
    # Getting Initial Pose & RPY
    pose_init = group.get_current_pose()
    rospy.loginfo( "Get Initial Pose\n{}".format( pose_init ) )
    rpy_init  = group.get_current_rpy()
    rospy.loginfo( "Get Initial RPY:{}".format( rpy_init ) )
    
    # Pose 1
    rospy.loginfo( "Starting Pose 1")
    group.set_start_state_to_current_state()
    
    pose_target_1 = Pose()
    pose_target_1.position.x =  0.20
    pose_target_1.position.y =  0.00
    pose_target_1.position.z =  0.15
    pose_target_1.orientation.x =  0.0
    pose_target_1.orientation.y =  0.0
    pose_target_1.orientation.z =  0.0
    pose_target_1.orientation.w =  1.0
    
    group.set_joint_value_target( pose_target_1, True )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )
    
    # Pose 2
    rospy.loginfo( "Starting Pose 2" )
    
    pose_target_2 = Pose()
    pose_target_2.position.x =  0.15
    pose_target_2.position.y =  0.15
    pose_target_2.position.z =  0.10
    pose_target_2.orientation.x =  0.0
    pose_target_2.orientation.y =  0.0
    pose_target_2.orientation.z =  0.3826834
    pose_target_2.orientation.w =  0.9238795
    
    group.set_joint_value_target( pose_target_2, True )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )
    
    # Pose 2 Z:+0.05[m]
    rospy.loginfo( "Starting Pose 2 Z:+0.05[m]")
    pose_target_2.position.z += 0.05
    
    group.set_joint_value_target( pose_target_2, True )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )
    
    # Back to Initial Pose
    rospy.loginfo( "Back to Initial Pose")
    group.set_joint_value_target( pose_init, True )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )

基本的な流れとしては Pose 型のインスタンス pose_target_1 などに位置・姿勢のデータを代入して group.set_joint_value_target( pose_target_1, True )で目標をセットし,group.go() で実行しています.

プログラムの実行方法は前述の MoveIt GUI でロボットが動作する状態にしてからもう1つターミナルを開いてテストプログラムを実行します.今回はテストプログラムのファイルを ~/catkin_ws/src/pro_moveit_config/script/uarm-sp_moveit_tutorial_poses.py としましたので,次のようにターミナルで実行しました.

$ rosrun pro_moveit_config uarm-sp_moveit_tutorial_poses

MoveIt Commander プログラムで uArm Swift Pro を動作せたときの動画です.

Open Manipulator X

<2022年8月31日追記>
本記事公開後に OpenManipulator-X のソフトウェア構成の変更があり,本記事で紹介した手順のアップデートが必要でしたので更新内容を新しい記事「“ROS 入門向けマニピュレータ導入検証” ROS Melodic & Noetic 対応更新」にて紹介しています.

Open Manipulator X のテストプログラムも基本は uArm Swift Pro と同様に set_joint_value_target( Pose, True ) を利用して作成しました.

追加的に Open Manipulator X の運動学上の「厳密解」の位置・姿勢データを予め計算しておいて set_pose_target() に与えたときの動作の様子もテストしました.

今回作成したテストプログラムを以下に記します.

Open Manipulator X – MoveIt Commander テストプログラム

#!/usr/bin/env python

import sys, math, copy
import rospy, tf, geometry_msgs.msg

from moveit_commander import MoveGroupCommander, RobotCommander
from geometry_msgs.msg import Pose, PoseStamped

if __name__ == '__main__':
    
    node_name = "commander_example"
    rospy.init_node( node_name, anonymous=True )
    
    group = MoveGroupCommander("arm")
    
    group.set_planning_time( 600.0 )
    
    # Getting Initial Pose & RPY
    pose_init = group.get_current_pose()
    rospy.loginfo( "Get Initial Pose\n{}".format( pose_init ) )
    rpy_init  = group.get_current_rpy()
    rospy.loginfo( "Get Initial RPY:{}".format( rpy_init ) )
    
    # Pose 1
    rospy.loginfo( "Starting Pose 1")
    pose_target_1 =  [ 0.12, 0.0, 0.1, 0.0, math.pi/2.0, 0.0 ] # [ x, y, z, r, p, y ]
    group.set_pose_target( pose_target_1 )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )
    
    # Pose 2
    rospy.loginfo( "Starting Pose 2")
    group.set_pose_target( [ 0.2, 0.0, 0.2, 0.0, 0.0, 0.0 ] )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )
    
    # Pose 3
    rospy.loginfo( "Starting Pose 3")
    
    pose_target_3 = Pose()
    pose_target_3.position.x =  0.10
    pose_target_3.position.y =  0.10
    pose_target_3.position.z =  0.10
    pose_target_3.orientation.x = -0.2706
    pose_target_3.orientation.y =  0.6533
    pose_target_3.orientation.z =  0.2706
    pose_target_3.orientation.w =  0.6533
    
    group.set_joint_value_target( pose_target_3, True )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )
    
    # Pose 3 Z:-0.05[m]
    rospy.loginfo( "Starting Pose 3 Z:-0.05[m]")
    pose_target_3.position.z -= 0.05
    
    group.set_joint_value_target( pose_target_3, True )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )
    
    # Pose 4
    rospy.loginfo( "Starting Pose 4")
    
    pose_target_4 = Pose()
    pose_target_4.position.x =  0.10
    pose_target_4.position.y = -0.10
    pose_target_4.position.z =  0.05
    pose_target_4.orientation.x =  0.2706
    pose_target_4.orientation.y =  0.6533
    pose_target_4.orientation.z = -0.2706
    pose_target_4.orientation.w =  0.6533
    
    group.set_joint_value_target( pose_target_4, True )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )
    
    # Pose 4 Z:+0.05[m]
    rospy.loginfo( "Starting Pose 4 Z:+0.05[m]")
    pose_target_4.position.z += 0.05
    
    group.set_joint_value_target( pose_target_4, True )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )
    
    # Back to Initial Pose
    rospy.loginfo( "Back to Initial Pose")
    group.set_joint_value_target( pose_init, True )
    group.go()
    
    rospy.sleep(5.0)
    pose_current = group.get_current_pose()
    rospy.loginfo( "Get Current Pose:\n{}\n".format( pose_current ) )

このテストプログラムのうち # Pose 1 と # Pose 2 の部分は set_pose_target() で目標姿勢を設定しています.このようにXZ平面上に位置する点の厳密解を指定した場合は set_pose_target() でも動作しましたが,# Pose 3 や # Pose 4 のようにXZ平面から外れたところは set_joint_value_target( Pose, True ) を利用しないと動作しませんでした.

プログラムの実行方法は前述の MoveIt GUI でロボットが動作する状態にしてからもう1つターミナルを開いてテストプログラムを実行します.今回はテストプログラムのファイルを ~/catkin_ws/src/pro_moveit_config/script/openmanipulatorx_moveit_tutorial_poses.py としましたので,次のようにターミナルで実行しました.

$ rosrun open_manipulator_moveit openmanipulatorx_moveit_tutorial_poses.py

Open Manipulator X を MoveIt Commander から動作させたときの動画です.

まとめ

今回 ROS の入門向けを念頭に2つのマニピュレータを導入し調査・検証しました.その結果を以下にまとめます.

  • 自由度が 6DOF 未満であることによる影響
    • MoveIt (GUI) では  “Allow Approx IK Solutions” のチェックを入れる必要あり
    • MoveIt Commander では目標姿勢のセットに set_joint_value_target() を使う必要あり
  • uArm Swift Pro に関して
    • ROS・MoveIt 対応パッケージの更新は滞っているように思える
      • MoveIt モデルの不備
      • MoveIt からの動作がカタカタする(遅い制御周期?)
    • ユーザ対応やユーザ間交流は ROS も含めてフォーラムで行われているよう
    • ロボット-PC 間が USB ケーブル1本で接続ができ簡単
    • Open Manipulator X に比べたら安価
  • Open Manipulator X に関して
    • eマニュアルが充実
    • Gazebo シミュレータあり
    • グリッパ付属
    • ロボット-PC 間に OpenCR ボードを挟み,そのポート設定も必要
      • OpenCR を使いこなせば拡張性が高い
    • uArm Swift Pro に比べたら高価

 総評

今回の2台のマニピュレータであれば Open Manipulator X の方が提供されている情報も多く,予算的に許されるのであれば入門に適していると思いました.

 

ROS 導入ノートパソコン比較調査
パソコン1台で出来るロボットの学習素材集

著者について

yamamoto.yosuke administrator

コメントを投稿するにはログインしてください。