著者アーカイブ yamamoto.yosuke

著者:yamamoto.yosuke

トランジスタ技術 2020年9月号 の ROS 入門の記事を執筆しました

トランジスタ技術 2020年9月号https://toragi.cqpub.co.jp/tabid/918/Default.aspx )の ROS 入門の記事を執筆しましたのでご紹介します.

東京オープンソースロボティクス協会は次の章を執筆しました.

(各章リンク先にサンプル PDF ファイルがあります)

これらの章では TORK の ROS ワークショップなどでつまづきやすかった点を踏まえて,次の内容をなるべく分かりやすく書いたつもりです.

  • ROS の概要や使うメリット
  • ROS の学習入門時のパソコンの選定
  • ROS を実行する Ubuntu Linux OS のパソコンへのインストール
  • ROS やロボットシミュレータのインストール方法とその利用
  • ROS のロボット動作計画・実行プログラムの実行や改造

続きを読む

著者:yamamoto.yosuke

パソコン1台で出来るロボットの学習素材集

ROS(ロス/Robot Operating System)の学習は実際にロボットがなくてもロボットのシミュレータが入手できるのでネットワークにつながるパソコンが1台あればできますので結構自習に向いています.この記事では ROS の学習を始める,進めるにあたり必要な情報がある Web へのリンクを中心に紹介します.

大まかに言うと次のインストールを行えば ROS の学習をスタートすることができます.

  • パソコンにオペレーティングシステムの Ubuntu Linux をインストール
  • Ubuntu Linux に ROS をインストール
  • ROS 上で動くロボットソフトウェアのインストール
    • → 紹介 ROS チュートリアル内にて

ROS と Ubuntu Linux のバージョンは後述する ROS 学習のチュートリアルが現時点では ROS Kinetic というバージョンを基本としているので下記の組み合わせをお勧めします.

  • Ubuntu 16.04
  • ROS Kinetic

ROS Melodic は ROS Kinetic と基本的な操作のほとんどは変わらないので ROS Kinetic で学習してから ROS Melodic に移行しても難なく可能です.

 

パソコンへの Ubuntu Linux のインストール

パソコンはどのようなものを使えば良いのか?については下記記事を参考にしてください.

ROS 導入ノートパソコン比較調査

ROS 導入ノートパソコン比較調査

最新高性能パソコンよりも数年型落ちや廉価の機種のほうが Ubuntu Linux をインストールしやすい傾向にあるように思います.

 

Ubuntu Linux への ROS のインストール

下記リンク先に各 ROS のバージョンにおけるインストール手順が書かれています.

また,Ubuntu のバージョンと ROS のバージョンには1対1の対応関係があるので組み合わせを気をつける必要があります.

 

ROS のチュートリアル

各チュートリアルを進めるとそれらの中で ROS シミュレータなどのインストールも行います.

TORK MoveIt チュートリアル

ROS の入門には TORK MoveIt チュートリアルをお薦めします.MoveIt は ROS のマニピュレーションロボット動作計画ソフトウェアです.このチュートリアルでは数種のロボットの ROS シミュレータのインストールや基本的な操作,プログラムでのロボット操作を学習することができます.TORK MoveIt チュートリアルではプログラミング言語に Python を用いていますが,プログラミングの経験がほとんどない人にもプログラムによるロボット操作の体験と学習ができるように構成しています.

ROS を初めて使う方に TORK MoveIt チュートリアルを学習したときのレポートも下記の記事に書いてもらっています.学習過程でいろいろと疑問をもった点などの体験を書いてもらいましたので参考にしてみてください.

初めてのROS(ROSチュートリアルを使って)

 

ROS-Industrial トレーニング(日本語版)

より発展的な ROS プログラミングを学習したい場合は ROS-Industrial トレーニングを行ってみるのも良いでしょう.この教材で取り上げられているプログラミング言語は主に C++ と Python です.C++ によるロボット制御や画像処理,3D ポイントクラウド処理などとそれらの組み合わせのプログラムの学習ができます.

ROS-Industrialのトレーニング教材を日本語訳しました!

 

ROS で質問したいことが出てきたら

ROS Discourse やチュートリアル,パッケージの GitHub Issues に質問を投稿してみてください.

 

入門的な実機マニピュレーションロボット

1台のパソコンだけ,シミュレータだけでなく入門的な実機マニピュレータを利用してみたいと思った方は入門的なマニピュレーションロボット2例の導入検証を行った記事を参考にしてみてください.

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

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

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

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

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

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

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")
    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 の方が提供されている情報も多く,予算的に許されるのであれば入門に適していると思いました.

 

著者:yamamoto.yosuke

ROS 導入ノートパソコン比較調査

TORK の ROS ワークショップを受講された方などから ROS を使用するにあたりどのような PC を利用したら良いかを問い合わせいただくことがあります.

基本的には利用したい ROS の各バージョンに対応した Ubuntu のバージョンが動作可能な PC であれば良いのですが,スペックが多岐にわたるパソコンの数々からどのようなパソコンを選んだら良いのか迷ってしまいます.

  • ROS Kinetic → Ubuntu 16.04 が動作可能な PC
  • ROS Melodic → Ubuntu 18.04 が動作可能な PC

そこで ROS を導入するパソコンの選定の参考なるよう,4つの異なる特徴のノートパソコンに実際に Ubuntu と ROS を導入して,その導入のポイントや動作結果を報告したいと思います.

  1. 10万円未満 モバイルノートパソコン : Dell Inspiron 13 5390
  2. 軽量モバイルノートパソコン : Dell XPS 13 7390
  3. モバイルワークステーション : Lenovo ThinkPad X1 Extreme 2nd Gen
  4. 2018年モデルモバイルノートパソコン : Lenovo ThinkPad T480s (既存品)

各ノートパソコン主要スペック

各ノートパソコンの主要なスペックは以下のとおりです.

Inspiron 13 5390 XPS 13 7390 ThinkPad X1 Extreme 2nd ThinkPad T480s
CPU Core i5-8265U Core i7-10710U Core i9-9880H Core i7-8550U
Threads / Cores 8 / 4 12 / 6 16 / 8  8/ 4
iGPU Intel UHD 620 Intel UHD 630 Intel UHD 630 Intel UHD 620
dGPU NVIDIA GeForce GTX 1650 Max-Q NVIDIA GeForce MX150
メモリ 8 GB 16 GB 32 GB 16 GB
SSD 256GB 512 GB 512GB + 1.0 TB 512 GB
ディスプレイサイズ 13.3″ IPS 13.3″ IPS 15.6″ IPS 13.3″ IPS
ディスプレイ解像度 1920 x 1080 3840 x 2160 (4K) 1920 x 1080 1920 x 1080
ディスプレイその他 グレア グレア・タッチ ノングレア ノングレア・タッチ
WiFi チップ Intel AC 9462 Intel AX200 Intel AX200 Intel AC 8265
電源 独自規格 USB-C 独自規格 USB-C
販売年 2019 2019 2019 2018
購入先 Amazon.co.jp Dell Lenovo
税込価格 ¥89,609.- ¥235,499.- ¥400,928.-
納期 即納 即納 約3週間
外観

Ubuntu Certified hardware

ROS / Ubuntu の導入機種を選ぶにあたって Ubuntu Certified hardware という Web ページが参考になります.

Ubuntu Certified hardware で今回の各ノートパソコンの対応状況を調べた結果が次の通りです.

これらのノートパソコンに限れば,2018 年の日付があるものは Ubuntu 16.04 に対応していて,2019 年の日付があるものは Ubuntu 18.04 に対応していると記載されています.

次項目で記述しますが対応が非明記のバージョンの Ubuntu をインストールしても問題なく動作する組み合わせもあります. Ubuntu Cetrified hardware を参考にしつつ,各ノートパソコンで使用されている各種チップの Linux デバイスドライバの対応状況等ふまえて導入を検討するのが良さそうです.

Ubuntu のインストール手順

Ubuntu はバージョン 16.04 と 18.04 をそれぞれのノートパソコンにインストールを試みました.各ノートパソコンに購入時にインストールされている Windows 10 を残したまま Ubuntu も起動できるように SSD にパーティションを切ってインストールすることとしました.

Ubuntu のインストール手順は Dell と Lenovo のノートパソコンで BIOS の設定方法が少し違うので分けて説明したいと思います.

なお,本記事では必要な手順の項目を中心にお伝えします.実際に PC に Ubuntu をインストールする際には具体的な方法を十分調査の上作業を行ってください.

Dell ノートPCへの Ubuntu のインストール手順

後述する Lenovo ThinkPad への Ubuntu のインストールと比べて BIOS の設定変更に関する手順が多くなっています.

  • Windows で記憶デバイスのパーティションを切って Ubuntu をインストールするディスク領域を確保
  • BIOS(UEFI) の設定変更
    • Secure Boot を OFF にする = USB メモリからのブートを可能にする
    • SATA Operation を RAID から ACHI モードに変更 = Linux ディスクにアクセスできるようにする
    • RAID モード(デフォルト)の状態で Windows を通常起動
    • 管理者権限でコマンドプロンプトを起動しbcdedit /set {current} safeboot minimal を実行
    • PC の再起動
    • PC 再起動時の Dell ロゴ画面にて F2 を押して BIOS(UEFI) 設定に入る
    • System Configuration の SATA Operation を RAID から ACHI に変更
    • APPLY CHANGES で設定変更を反映させてから EXIT にて再起動
    • Windows 10 のセーフモードの起動
    • 管理者権限でコマンドプロンプトを起動して bcdedit /deletevalue {current} safeboot を実行
  • Ubuntu Linux のインストール
    • Ubuntu インストーラの入っている USB メモリを PC に接続
    • PC の起動
    • PC 再起動時の Dell ロゴ画面にて F12 を押して One-Time Boot Settings に入る
    • Ubuntu インストーラの入っている USB メモリを選択して起動
    • Ubuntu のインストールの実行
  • デバイスドライバのアップデート・インストール
    • インターネットに接続した状態で Ubuntu のソフトウェアのアップデートを行う
    • XPX 13 7390
      • Ubuntu 18.04 には Dell からデバイスドライバが用意されているのでダウンロードしてインストールする
      • Ubuntu 16.04 にはデバイスドライが対応していない
        • ディスプレイのスケーリングができない = 文字が小さすぎて見えない
        • WiFi チップの Intel AX200 がドライバ対応されていない
          • USB 接続の有線 Ethenet なら利用可能

インストールにあたっては次のサイトを参考にしました.

Lenovo ThinkPad ノートPCへの Ubuntu のインストール手順

  • Windows で記憶デバイスのパーティションを切って Ubuntu をインストールするディスク領域を確保
  • BIOS の設定変更
    • 起動時 Lenovo ロゴ画面で Enter を押した後にメニューに従って F1 で BIOS Setup Utility に入る
    • Security Chip の無効化
    • Secure Boot の無効化
  • Ubuntu のインストール
    • Ubuntu インストーラの入っている USB メモリを PC に接続
    • PC の起動
    • 起動時 Lenovo ロゴ画面で Enter を押したあとにメニューに従って F12 で choose a temporary startup device を選択
    • Ubuntu インストーラの入っている USB メモリを選択して起動
    • Ubuntu のインストールの実行
  • デバイスドライバのアップデート・インストール
    • インターネットに接続した状態で Ubuntu のソフトウェアのアップデートを行う
    • NVIDIA GeForce ドライバの適用
      • グラフィックドライバのリポジトリの追加
        • sudo add-apt-repository ppa:graphics-drivers/ppa
        • sudo apt-get update
      • Software Updater → Settings … → Additional Drivers → nvidia-driver-440 → Apply changes
    • ThinkPad X1 Extreme のみ
      • WiFi チップの Intel AX200 がドライバ対応されていない
        • USB 接続の有線 Ethenet なら利用可能

Dell と Lenovo のノートPCインストール手順の比較・総評

  • Dell に比べて Lenovo ThinkPad の方が BIOS 関連の設定変更が楽
    • Dell の SATA Operation を RAID から ACHI モードに変更する手順が複雑
  • Ubuntu インストール後アップデート作業までは…
    • WiFi 接続ができないので USB 接続有線 Ethernet アダプタが必要
    • タッチパッドが機能しない可能性があるので USB 接続のマウスが必要
  • 13インチ 4K ディスプレイはスケーリングが適用されるまでは文字が小さくて非常に見づらい
  • Ubuntu 16.04 においては WiFi チップ Intel AX200 のドライバを適用しても WiFi に接続しようとすると OS がフリーズした
  • 最新のチップ構成だと Linux ドライバが対応していない可能性に注意
  • Ubuntu 18.04 は今回試したいずれの PC でも正常に動作可能と言える
  • Ubuntu Certified hardware で各 PC の Ubuntu バージョンの対応関係は参考になる

ベンチマークテスト

CPU ベンチマーク比較

各 PC で UnixBench を実行して,シングルコア・マルチコアのスコアを調査しました.

Dell Inspiron 13 5390 Dell XPS 13 7390 ThinkPad X1 Extreme Gen2 ThinkPad T480s
スペック
CPU ナンバー Core i5-8265U Core i7-10710U Core i9-9880H Core i7-8550U
スレッド / コア 8 / 4 12 / 6 16 / 8 8 / 4
ベース周波数 1.6 GHz 1.1 GHz 2.3 GHz 1.8 GHz
最大周波数 3.9 GHz 4.7 GHz 4.8 GHz 4.0 GHz
UnixBench
シングルコア 1640.1 2106.8 1829.1 1234.6
マルチコア 3550.8 6012.3 7960.4 3399.5

Multi Cores はコア数に応じたスコアを示しているように思います.

また Dell Inspiron 13 5390 が値段の割に良い結果が得られました.

GPU ベンチマーク比較

GPU は ROS では Gazebo シミュレーションの 3D 表示能力などと関係がある項目です.

各 PC で Unigine Benchmark – Heaven (1920 x 1080) と glmark2 をそれぞれ実行して,スコアを調査しました.

Dell Inspiron 13 5390 Dell XPS 13 7390 ThinkPad X1 Extreme Gen2 ThinkPad T480s
GPU Intel UHD 620 Intel UHD 630 Intel UHD 630 GeForce GTX 1650 Intel UHD 620 GeForce MX150
Unigine Benchmark – Heaven 1920 x 1080
Score 281 310 290 1565 267 548
FPS 11.2 12.3 11.5 62.1 10.6 21.8
Min FPS 5.0 5.9 8.1 21.4 5.3 6.3
Max FPS 23.7 25.9 23.2 124.7 22.1 46.2
glmark2
Score 2244 2892 2978 2633 2500 3343

Unigine Benchmark – Heaven では NVIDIA グラフィックの優位性が顕著に出ました.

一方 glmark2 の方は NVIDIA GeForce MX150 の優位性はあるものの NVIDIA GeForce GTX 1650 はむしろ Intel UHD 630 よりも低いスコアとなりました.これらの PC では glmark2 実行時に 2000 〜 4000 fps ほど出てしまうので,現在の GPU に対しては負荷が軽すぎるような印象を持ちました.

ROS PCL プロセス処理周波数比較

実際の ROS プロセスの動作状況を比較するためにポイントクラウドのフィルタリング処理能力を比較しました.

予め記録したポイントクラウドメッセージの rosbag データを各 PC で Voxel Grid フィルタと Statistical Outlier Removal フィルタをかけて ROS トピック /camera/statistical_outlier_removal/output として出力して周波数を調査しました.

$ rostopic hz /camera/statistical_outlier_removal/output
Dell Inspiron 13 5390 Dell XPS 13 7390 ThinkPad X1 Extreme Gen2 ThinkPad T480s
MAX 2.855 5.052 4.333 2.000
Average 2.353 3.759 3.830 1.873
min 2.126 2.975 3.623 1.787

3D グラフィクの表示は行わなかったので基本的には CPU によるデータ処理と考えられます.

CPU Multi Cores のスコアが一番近い傾向にあるように思いますが,Dell XPS 13 と ThinkPad X1 Extreme Gen2 の差は CPU Multi Cores ほどは出ませんでした.より多い数のスレッドを必要とするプロセスでは差が出るかもしれません.また Dell XPS 13 7390 は処理周波数の最大,最小の差が大きかったです.

Dell Inspiron 13 5390 は値段の割に良い結果を出している印象を持ちました.

まとめ

  • インストール・設定関係
    •  BIOS
      • Lenovo ThinkPad の方が Dell に比べて BIOS 関連の設定変更が楽
    • 13インチ 4K ディスプレイ(今回は Dell XPS 13 7390)
      • スケーリングが適用できるようになるまでは文字が小さくて非常に見づらい
    • Ubuntu 18.04 は今回試したいずれの PC でも正常動作
    • Ubuntu 16.04 においては一部 WiFi チップ Intel AX200 のドライバに不具合
    • 最新のチップ構成だと Linux ドライバが対応していない可能性に注意
    • Ubuntu Cetrified hardware で各 PC の Ubuntu バージョンの対応関係は参考になる
  • 各ノートパソコン性能など
    • Dell Inspiron 13 5390
      • 10万円未満という値段の割には良い性能
        • 低コストやドライバ対応の面を考えると Ubuntu + ROS 入門用に向いている
          • ただ BIOS の設定に手間がかかる
    • Dell XPS 13 7390
      • 今回の ROS ポイントクラウド処理では ThinkPad X1 Extreme に肉薄する性能
    • ThinkPad X1 Extreme Gen2
      • CPU・GPU・ROS PCL の全ベンチマークで最高性能を発揮
    • ThinkPad T480s
      • Intel GPU に比べて NVIDIA GPU の優位性あり
      • BIOS 設定も簡単で基本的なドライバは追加する必要もなくインストールが楽
  • その他
    • グレアディスプレイだと写真や動画を撮るときに反射・映り込みに配慮する必要あり
Dell Inspiron 13 5390 Dell XPS 13 7390 ThinkPad X1 Extreme Gen2 ThinkPad T480s
Ubuntu 16.04 + ROS Kinetic
Ubuntu 18.04 + ROS Melodic
BIOS 設定の容易さ
ROS ポイントクラウド処理性能
価格
著者:yamamoto.yosuke

CIS ToF カメラセンサ がネット購入できるようになりました

2019年に ROS パッケージをリリースしました CIS ToF カメラセンサ DCC-RGBD1 がネットから購入できるようになりました.

Amazon.co.jp で購入の場合は日本国内への出荷のみですが,日本国外へも 株式会社シーアイエス の販売窓口メールアドレス ec-sales@ciscorp.co.jp にお問い合わせいただくと販売可能とのことです.

著者:yamamoto.yosuke

CIS ToF カメラセンサの ROS ドライバパッケージをリリースしました

新しい ROS パッケージ cis_camerahttps://github.com/tork-a/cis_camera )をリリースしました.

この ROS パッケージは 株式会社シーアイエスhttps://www.ciscorp.co.jp/ ) ToF (Time of Flight) カメラセンサ DCC-RGBD1 のためのドライバパッケージです.

DCC-RGBD1 は小型ながら広いレンジの深度画像が取得可能な ToF カメラセンサ(ディベロップメントキット)です.

  • 15cm 〜 5m のレンジで高精度な深度画像を取得可能
  • 小型 H:50mm × W:55mm × D:35mm(突起部を含まず)
  • RGB (QVGA) と Depth / IR (VGA) の3つの画像を同時取得
  • インタフェースは USB 3.0( USB 3.0 micro B コネクタ搭載:USB 給電は非対応 )
  • 屋内使用向け

本パッケージでは CIS ToF カメラセンサの ROS ドライバに加え,ノイズ除去,平面検出・除去,対象物点群抽出とフレーム座標算出のポイントクラウド処理ならびに,それらの処理結果を RViz で 3D 表示するためのサンプルプログラムおよび launch ファイルを同梱しています.

使い方は GitHub のドキュメントをご参照ください.
もし問題にぶつかった場合は GitHub Issues で報告をお願いします.

CIS ToF カメラセンサのハードウェアの入手などに関するお問い合わせは下記連絡先までお願いします.

ハードウェアに関するお問合せ先:株式会社シーアイエス 営業担当
メールアドレス:newbiz@ciscorp.co.jp
電話番号:042-664-5568