タグアーカイブ model

著者:yamamoto.yosuke

Gazebo/MoveIt のための 3D モデリング(14)MoveIt の動モデルの作成

本シリーズ前回の記事 Gazebo/MoveIt のための 3D モデリング(13)MoveIt の静モデルの作成 では CAD などからエクスポートしたメッシュデータファイルを MoveIt の静モデルとしてモデルファイルに組み込んで表示する方法を紹介しました.

今回は洗濯機の URDF (Unified Robot Description Format) モデルにドアのヒンジなどの動く箇所を設定して,より機械らしい(ロボットに近い)モデルにする様子を紹介します.

各リンクモデルメッシュのエクスポート

前回の MoveIt の静モデル作成においては洗濯機全体として1つのメッシュデータファイル( DAE もしくは STL )をエクスポートして利用しました.

MoveIt のリンクモデル作成では各リンクに対応したメッシュをそれぞれエクスポートしてそれぞれのリンクのメッシュファイルとして利用します.

今回の洗濯機モデルでは次の3つのリンク構成にします.

  • 洗濯機本体: main-body
  • 洗濯槽の扉: door
  • 洗剤投入トレイ: tray

今回は「洗濯機本体(main-body)」は元の洗濯機全体の座標系そのままとするので配置の変更はしません.

「洗濯槽の扉(door)」と「洗剤投入トレイ(tray)」の形状データを各リンクの座標系原点に配置します.

元々の洗濯機全体の座標系で配置されたオブジェクトを残しつつ,別途各リンクのエクスポート用にリンク座標系の原点にオブジェクトを配置してメッシュデータとしてエクスポートします.

Rhinoceros では右の図のようにオブジェクトを含む既存のレイヤを右クリックするとメニューに「レイヤとオブジェクトを複製」ができるのでこの機能で複製した先のレイヤで作業すると良いでしょう.

各リンク座標系基準の配置用レイヤでそれぞれの各リンクは次のように配置しました.

  • 洗濯機本体: main-body
    • 位置: 変更なし
    • 角度: 変更なし
  • 洗濯槽の扉: door
    • 位置: 開閉ヒンジ回転軸の中心が座標原点
    • 角度: 開閉ヒンジ回転軸を Z軸 に一致
  • 洗剤投入トレイ: tray
    • 位置: 最後下部エッジ中心が座標原点
    • 角度: 変更なし

各リンク座標基準に配置したオブジェクトを選択して「選択オブジェクトをエクスポート」コマンドから DAE (Collada) か STL 形式でエクスポートします.

Rhinoceros から DAE (Collada) をエクスポートする場合はエクスポートオプションにて
ジオメトリのみを保存」のみにチェック
を入れてファイルを書き出します.

この「ジオメトリのみを保存」でも色や単位情報も保存されます.

今回は表示(visual)用に色付きの DAE ファイルとしてエクスポートし,干渉チェック(collision)用にデータ量を少なくするため粗目の設定で STL ファイルをエクスポートしました.

  • 表示 visual 用 DAE ファイル
    • main-body.dae
    • door.dae
    • tray.dae
  • 干渉チェック collision 用 STL ファイル
    • main-body.stl
    • door.stl
    • tray.stl

リンク機構を含む URDF モデルファイルの作成

DAE や STL のメッシュデータのエクスポートが終わったらリンク機構を含む URDF モデルファイルを作成します.

ファイル配置

3dmodeling-examples/models/urdf/
├── meshes
│   └── washing-machine
│       ├── base_link.dae
│       ├── base_link.stl
│       ├── door.dae
│       ├── door.stl
│       ├── main-body.dae
│       ├── main-body.stl
│       ├── tray.dae
│       └── tray.stl
├── washing-machine_links.urdf
└── washing-machine.urdf

前回作成してメッシュファイルを配置したフォルダ
3dmodeling-examples/models/urdf/meshes
内にエクスポートしたメッシュファイルを配置します.

そしてフォルダ 3dmodeling-examples/models/urdf/ にファイル washing-machine_links.urdf をテキストファイルとして作成してそこにリンク機構を含む URDF モデルを作り込みます.前回作成したファイル washing-machine.urdf を複製してファイルの名前を変更しても良いです.

リンクの相対姿勢・可動域の確認

URDF データで 「洗濯機本体(main-body)」 と 「洗濯槽の扉(door)」 および 「洗剤投入トレイ(tray)」 それぞれの相対的な姿勢の関係とそれぞれの可動域を 「関節(joint)」 として定義しますので, CAD ( Rhinoceros など ) 上で相対姿勢および可動域の測定を行います.

その際,各リンクオブジェクトについて DAE や STL ファイルへのエクスポート用に原点へ移動した配置ではなく元々の洗濯機全体内での配置で調べるということに注意してください.

まずは 「洗濯機本体(main-body)」 と並進的な相対位置関係にある 「洗剤投入トレイ(tray)」 の座標の確認と設定可能な可動域を調べます.

  • 洗濯機本体(main-body) → 洗剤投入トレイ(tray)
    • 相対位置: 洗濯機本体原点から ( 0.0 , -190.00 , 956.00 ) [mm] の位置
    • 相対角度: ゼロ
    • 可動域: 前方へ 200 [mm] とした

次に 「洗濯機本体(main-body)」 と 「洗濯槽の扉(door)」 の相対座標・角度やの確認と設定可能な可動域を調べます.

扉は傾いて洗濯機本体に取り付けられているのでその角度とヒンジ回りの可動域も調べます.Rhinoceros では角度表示がラジアンでもできるのでそれを利用します.

  • 洗濯機本体(main-body) → 洗濯槽の扉(door)
    • 相対位置: 洗濯機本体原点から ( 306.58 , -258.00 , 675.82 ) [mm] の位置
    • 相対角度: 洗濯槽の扉(door)原点から Y軸と平行な軸 回りに 0.1396 [rad] (= 8.0 [deg] )
    • 可動域: ヒンジを軸に閉じた状態から 1.8326 [rad] (= 105 [deg] ) 開くとした

URDF データの作成

リンクモデルに必要なメッシュファイルと情報が揃いましたので URDF ファイルに書き込んだものが次のようになります.

washing-machine_links.urdf
<?xml version="1.0" ?>

<robot name="washing-machine">
  
  <link name="base_link">
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://3dmodeling-examples/models/urdf/meshes/washing-machine/main-body.stl" scale="0.001 0.001 0.001" />
      </geometry>
    </collision>
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://3dmodeling-examples/models/urdf/meshes/washing-machine/main-body.dae" />
      </geometry>
    </visual>
  </link>
  
  <link name="door">
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://3dmodeling-examples/models/urdf/meshes/washing-machine/door.stl" scale="0.001 0.001 0.001" />
      </geometry>
    </collision>
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://3dmodeling-examples/models/urdf/meshes/washing-machine/door.dae" />
      </geometry>
    </visual>
  </link>
  
  <link name="tray">
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://3dmodeling-examples/models/urdf/meshes/washing-machine/tray.stl" scale="0.001 0.001 0.001" />
      </geometry>
    </collision>
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://3dmodeling-examples/models/urdf/meshes/washing-machine/tray.dae" />
      </geometry>
    </visual>
  </link>
  
  <joint name="joint1" type="revolute">
    <parent link="base_link"/>
    <child  link="door"/>
    <origin xyz="0.30658 -0.258 0.67582" rpy="0 -0.1396 0"/>
    <axis xyz="0 0 1" />
    <limit effort="30" velocity="1.0" lower="-1.8326" upper="0.0" />
  </joint>
  
  <joint name="joint2" type="prismatic">
    <parent link="base_link"/>
    <child  link="tray"/>
    <origin xyz="0.0 -0.190 0.956" rpy="0 0 0"/>
    <axis xyz="1 0 0" />
    <limit effort="30" velocity="1.0" lower="0.0" upper="0.200" />
  </joint>
  
</robot>

washing-machine_links.urdf 内のそれぞれの要素について説明します.

  • 5〜48行 <link> 要素: リンクの定義 3つ ( base_link, door, tray )
    • <collision> 要素にメッシュに STL ファイルを使用し単位変換 [mm] → [m]
    • <visual> 要素に DAE メッシュファイルを使用
    • <origin> はリンク内のメッシュの配置なので今回は全てゼロ
  • 50〜56行 <joint> 要素: joint1
    • type で関節形式 revolve (=回転)を設定
    • <parent> 要素で関節を介する親リンク base_link を指定
    • <child> 要素で関節を介する子リンク door を指定
    • <origin> 要素で親子リンク間の相対座標
      • 位置の単位はメートル [m]
      • 姿勢角の正負に注意(座標軸に対して右ねじの法則)
    • <axis> 要素で revolve 関節の回転軸のリンク座標系での方向を設定
    • <limit> 要素
      • effort : 最大トルク – 今回はとりあえずの値
      • velocity : 最大角速度 – 今回はとりあえずの値
      • lower : 可動域下限 – 回転関節なので下限角度で単位はラジアン [rad]
      • upper : 可動域上限 – 回転関節なので上限角度で単位はラジアン [rad]
  • 58〜64行 <joint> 要素: joint2
    • type で関節形式 prismatic (=並進)を設定
    • <parent> 要素で関節を介する親リンク base_link を指定
    • <child> 要素で関節を介する子リンク tray を指定
    • <origin> 要素で親子リンク間の相対座標
    • <axis> 要素で prismatic 関節のリンク座標系での移動方向を設定
    • <limit> 要素
      • effort : 最大力 – 今回はとりあえずの値
      • velocity : 最大速度 – 今回はとりあえずの値
      • lower : 可動域下限 – 並進関節なので下限位置で単位はメートル [m]
      • upper : 可動域上限 – 並進関節なので上限位置で単位はメートル [m]

下記リンク先の ROS Wiki に URDF ファイルの作成方法のチュートリアルがありますので参考にしてください.

URDF モデルの確認

urdf_tutorialdisplay.launch で URDF モデル washing-machine_links.urdf の確認をします.(下記コマンド横スクロールで末尾まで表示)

$ roslaunch urdf_tutorial display.launch model:='$(find 3dmodeling-examples)/models/urdf/washing-machine_links.urdf'

URDF で <joint> 要素を定義して joint_state_publisher ウィンドウ内のスライドバーも有効になっているので関節を動かしてみます.

動画では表示メッシュの動きとともに TF も一緒に動いている様子が見られると思います.

今回の記事はここまでです.

著者:yamamoto.yosuke

Gazebo/MoveIt のための 3D モデリング(13)MoveIt の静モデルの作成

本シリーズ前回の記事 Gazebo/MoveIt のための 3D モデリング(12)Gazebo の静モデルの作成 ではエクスポートしたメッシュデータファイルを Gazebo の静モデルとしてモデルファイルに組み込んで表示する方法を紹介しました.

今回はエクスポートしたメッシュデータファイルを MoveIt の静モデルとしてモデルファイルに組み込んで表示する方法を紹介します.

今回紹介するのは次の2通りの方法です.メッシュを MoveIt GUI で読み込んで障害物とする方法とロボットモデル作成につながる方法の URDF モデルの作成とそれを確認表示する方法です.

  1. MoveIt 空間内の動作計画に対する障害物として STL ファイルまたは DAE ファイルを読み込んで設置
  2. URDF モデルの作成(→ ロボットリンクモデル作成へつながる)

MoveIt 内の障害物モデルとしてのメッシュ読込み

MoveIt には動作計画における障害物として STL ファイルや DAE ファイルをそのまま読み込んで MoveIt の動作計画空間内に配置する機能があります.

MoveIt の Motion Planning パネル内の Scene Objects タブを開いて, “Mesh from file” を選択します.

“Mesh from file” セレクタの右隣にあるプラスボタン [ + ] を押します.

(左図拡大は画像をクリック)

保存してある STL もしくは DAE ファイルを選択します.

ファイルを読み込むときに MoveIt の GUI インタフェースである RViz のメッセージウィンドウが開いて,ミリメートル単位で記述されているモデルをメートル単位に変換する旨の問いがなされるので [ Yes ] をクリックします.

読み込んだモデルをインタラクティブマーカや座標などを指定して意図した位置に設置し,左のチェックボックスをクリックすると設置リンクの選択を促されますので適宜選択して [ OK ] ボタンを押します.

次に [ Publish ] ボタンを押すと読み込んで設置したモデルが MoveIt 空間内で障害物として認識されます.

あとは [ Plan ] や [ Plan & Execute ] などで動作計画を実行するとその経路上に障害物があるとそれを避けたマニピュレーションの軌道が生成されます.

MoveIt モデル URDF ファイルの作成

MoveIt モデルの URDF ファイルの作成は下記リンク先の ROS Wiki に書かれています.
本記事ではそれらから MoveIt 静モデル作成に絞って説明します.

MoveIt モデルの作成にあたっては ROS パッケージを作成してその中にモデルの URDF ファイルを置くのが本記事の内容に続く応用も含めると一番簡便なのではないかと思います.

今回 ROS パッケージをつくるのが面倒なようでしたら下記リンク先リポジトリをクローンして利用してください.

3dmodeling-examples/
├── CMakeLists.txt
├── images
│   ├── front_view_win.png
│   ├── left_view_win.png
│   ├── top_view_win.png
│   ├── washing-machine_catalogue.pdf
│   └── washing-machine_catalogue.png
├── launch
│   ├── spawn-washingmachine.launch
│   └── world-washingmachine.launch
├── LICENSE
├── models
│   ├── gazebo_models
│   │   ├── washing-machine
│   │   │   ├── meshes
│   │   │   │   ├── base_link_blue-gray.stl
│   │   │   │   ├── base_link_dark-gray.stl
│   │   │   │   ├── base_link_gray-white.stl
│   │   │   │   ├── base_link_light-gray.stl
│   │   │   │   └── base_link.stl
│   │   │   ├── model.config
│   │   │   └── model.sdf
│   │   └── washing-machine-dae
│   │       ├── meshes
│   │       │   ├── base_link.dae
│   │       │   └── base_link.stl
│   │       ├── model.config
│   │       └── model.sdf
│   ├── urdf
│   │   ├── meshes
│   │   │   └── washing-machine
│   │   │       ├── base_link.dae
│   │   │       └── base_link.stl
│   │   └── washing-machine.urdf
│   └── washing-machine.3dm
├── package.xml
├── README.md
└── worlds
    └── washing-machine.world

本記事執筆時のサンプルモデルパッケージは右に示すような構成になっていますので参考にしてみてください.

この中の MoveIt URDF モデルに関連するフォルダ・ファイルがハイライトされた部分です.

meshes フォルダに base_link.dae と base_link.stl の2つのファイルが含まれていますが,これはサンプルのためですのでどちらか1つのファイルだけでも URDF モデルは作成できます.

今回の MoveIt 静モデルのサンプル URDF ファイル washing-machine.urdf の中身は次のようになっています.

<?xml version="1.0" ?>

<robot name="washing-machine">
  
  <link name="base_link">
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://3dmodeling-examples/models/urdf/meshes/washing-machine/base_link.stl" scale="0.001 0.001 0.001" />
      </geometry>
    </collision>
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://3dmodeling-examples/models/urdf/meshes/washing-machine/base_link.dae" />
      </geometry>
    </visual>
  </link>
  
</robot>

URDF のデータ形式は XML で,モデル構成要素の linkcollisiongeometrymesh が記述されています.今回は静モデルですので link 要素は1つですがロボットのように関節が多いとリンク数にともなって link 要素およびそこに含まれる子要素も増えます.

ROS パッケージ化していることで ROS のファイルシステムが名前空間から package://3dmodeling-examples/... によって 3dmodeling-examples パッケージのディレクトリを自動解決できるようになっています.

collision メッシュの STL データは単位情報を持っていないので scale="0.001 0.001 0.001" で 0.001倍(=1/1000) 変換をして [mm] のデータを [m] に換算しています.

  • 注) 表示上コードの右の方に隠れていると思うので横スクロールで確認してください.

visual のメッシュは DAE ファイルを利用していて,DAE モデルは単位情報を持っていて読み込む側でスケール判断をするので scale は必要ありません.

URDF モデルファイルの RViz 表示

URDF モデルの確認には urdf_tutorial パッケージの display.launch を利用します.

urdf_tutorial は joint-state-publisher-gui パッケージをインストールすることで利用できるようになります.下記は ROS Melodic の場合のインストールコマンドですので他の ROS バージョンの場合は melodic の部分を noetic などに書き換えて実行してください.

$ sudo apt update
$ sudo apt install ros-melodic-joint-state-publisher-gui

ターミナルで ROS 環境の設定と urdf_tutorial の display.launch の起動を行います.

$ source ~/$PathToYourWorkspace/devel/setup.bash
$ roslaunch urdf_tutorial display.launch model:='$(find 3dmodeling-examples)/models/urdf/washing-machine.urdf'
  • 注)
    • $PathToYourWorkspace は各自の ROS ワークスペースへのパスを記述
    • Launch オプションの model:= には URDF ファイルパスを指定
      • 上記は 3dmodeling-examples パッケージ内のフォルダに washing-machine.urdf がある場合の例

正常に実行できると次の図のように洗濯機モデルが RViz 空間上に表示されます.

今回の単一リンクの正モデルの場合はリンク(フレーム)間の座標変換(tf)が無いので RViz 内の “Global Status: Warn / Fixed Frame No tf data. Actual error: Fixed Frame does not exist” と警告が出ますが問題はありません.
問題はありませんが気持ちの収まりが悪いようでしたらターミナルを追加で立ち上げて下記コマンドで例えば /world フレームから洗濯機モデルの /base_link フレームへの tf をパブリッシュすると警告が消えます.

$ rosrun tf2_ros static_transform_publisher 0 0 0 0 0 0 /world /base_link

今回の記事はここまでです.


本シリーズ次回の記事は洗濯機の URDF モデルにドアのヒンジなどの動く箇所を設定してより機械らしい(ロボットに近い)モデルにする様子を紹介する予定です.

著者:yamamoto.yosuke

Gazebo/MoveIt のための 3D モデリング(11)形状データのエクスポート

本シリーズ前回の記事 Gazebo/MoveIt のための 3D モデリング(10)部品作成編 で洗濯機全体の形状が完成しました.

まずはエクスポートするメッシュの確認も兼ねて,可動部分のない一番単純な Gazebo と MoveIt それぞれにおける洗濯機モデルを作ることを目標として,今回は CAD( 本記事では Rhinoceros )の形状データに色を付けるとともに Gazebo や MoveIt で利用できるデータ形式にエクスポートする手順を紹介します.

次の図は今回エクスポートするデータを Gazebo と MoveIt のシミュレーションモデルに組み込んで表示させた様子で,次回の記事のゴールになる予定です.

Gazebo/MoveIt モデルに必要なメッシュデータ

Gazebo/MoveIt のシミュレーションモデルにはディスプレイ表示用の visual メッシュと干渉チェック用の collision メッシュの2種類のデータが必要です.今回は大きく分けて次の ① ② ③ の 3種類 のデータを用意します.

  • MoveIt 用 URDF モデル
    • visual : Collada(DAE)データ ①
      • DAE ファイルには色と単位の情報も「含まれる」
    • collision : 物体領域を明確に分けられる閉じた STL メッシュ(群)データ ②
  • Gazebo 用 SDF モデル
    • visual : 各表示色別に分けた STL メッシュデータ ③(今回は4色4ファイル)
      • STL ファイルには色と単位の情報が「含まれない」ため SDF ファイル側で指定
    • collision : 物体領域を明確に分けられる閉じた STL メッシュ(群)データ ②

一般的には visual メッシュを少し細かく(データとしては重く)し,collision メッシュは粗く(データとしては軽く)することが多いです.Gazebo シミュレータは物理エンジンも含まれていますのでロボットの力制御シミュレーションをするようになってくると collision メッシュの方をより細かくする必要が出てくるかもしれません.

干渉チェック(collision)用 STL メッシュデータのエクスポート

ひとまず可動部分のない Gazebo および MoveIt のシミュレーションモデルを作成しますので,これまで作成してきた洗濯機モデルの閉じたポリサーフェス(=ソリッド)をそのまま全て選択して「選択オブジェクトをエクスポート(Export)」で干渉チェック用の STL メッシュデータファイルとしてエクスポートします.

  • 選択オブジェクトをエクスポート
    • メニュー: ファイル(F) > 選択オブジェクトをエクスポート(E)
    • コマンド: Export

ファイルの種類で「STL (Stereolithography) (*.stl)」を選択します.ファイル名はメッシュモデルの乗るシミュレーションモデルのリンク名にすると分かりやすいので今回は「base_link.stl」とします.

ポリゴンメッシュ詳細オプション」の子ウィンドウが出るので各設定項目は主に下のリストのように今回は設定しました.(図はクリックで拡大表示されます.)

  • 最小エッジ長さ(E): 0.0001
  • 最大エッジ長さ(L): 0.0 (=無指定)
  • エッジからサーフェスの最大距離(D): 0.1
  • メッシュをリファイン(R): チェック

STL メッシュデータの粗密やデータ量を調整したい場合は主にこれらの設定値を調整します.

STLエクスポートオプション」ではデータ量を確認してデータが大きすぎるような場合には「メッシュを調整」ボタンから再調整して,問題なければ「バイナリ(B)」でエクスポートします.

エクスポートした STL ファイルの内容を確認するにはフリーソフトウェアの MeshLab にインポートするのが良いのではないかと思います.

MeshLab は Windows・Mac・Linux のどのプラットフォームにもインストールできますので便利です.

また Windows であれば「3Dビューアー」,Mac であれば「プレビュー」でも STL ファイルを表示することが可能です.

エクスポートした STL ファイルに洗濯機全体の形状データが含まれているように表示されるかと思います.

干渉チェック(collision)用の STL ファイルへのエクスポート手順は以上です.

洗濯機各部の色付け

ディスプレイ表示用の visual メッシュは色を付けない単色での利用も可能ですが,せっかくなのでカタログから推測して次のリストの色分けをしてみます.

  • gray-white: 本体の前面・上面側面の大部分
  • light-gray: ドア枠と本体側周辺部品・背面
  • dark-gray: 底部周辺
  • blue-gray: ドアの透明窓部・液晶表示部

Rhinoceros のデフォルトではポリサーフェスで1つにまとまっていると色や反射率,透過率などの設定が含まれるマテリアル設定が1つしか反映されないので,色ごとのポリサーフェスやサーフェス,それらのグループに分解します.ソリッド(=閉じたポリサーフェス)の状態は残しておきたいので色付け用のレイヤを作成してそのレイヤに洗濯機モデル全体をコピーしたものを分解,色付けします.

色はオブジェクトの「マテリアル」を設定して付けます.

色ごとに分けたオブジェクト(=ポリサーフェスやサーフェス,グループ)を選択してから右クリックして「オブジェクトのプロパティ(S)」を表示して「プロパティ: マテリアル」タブを開きます.

マテリアルの設定時に気を付ける点があり,「金属」系の色は後の項目でエクスポートする Collada(DAE)ファイルや Gazebo,MoveIt のディスプレイ上では反映されなく,意図しない,おそらくエクスポートしたオブジェクトのあるレイヤー色か黒などに表示されてしまうので「プラスチック」系のマテリアルを使用して各色を指定するのが良さそうです.

また,Rhinoceros 上での表示形式を「レンダリング」にすることでマテリアルが反映された表示になります.

上の図では 「gray-white」を選択した例を示していますが,他の「light-gray」「dark-gray」「blue-gray」についても同様にプラスチック系マテリアルの色を調整して設定します.

Collada(DAE)メッシュデータのエクスポート

MoveIt シミュレーションモデルの URDF ファイルから表示用(visual)メッシュとして使うために,マテリアルを設定して色付けしたモデル Rhinoceros から Collada(DAE)ファイルとしてエクスポートします.

Collada(DAE)のメッシュデータには色や単位の情報も含まれるので全色分のオブジェクトを一緒くたに選択して「選択オブジェクトをエクスポート(Export)」でエクスポートします.

ファイルの種類に「COLLADA(*.dae)」を選択します.ファイル名はメッシュモデルの乗るシミュレーションモデルのリンク名にすると分かりやすいので今回は「base_link.dae」とします.

エクスポートした DAE ファイルの内容の確認は Mac だと「プレビュー」で右の図のように行えます.

FreeCAD は Windows や Mac,Linux で利用でき,DAE データも表示することができます.

FreeCAD の操作感はあまり良いとは言えないのですが様々な形式の 3D データが読み込めるのでデータ確認には非常に便利です.

金属マテリアル表現の 3D モデルについて

今回,洗濯機操作部の丸いボタンに金属系マテリアルを設定して Collada(DAE)ファイルとしてエクスポートして利用しようとしましたが金属マテリアル部分が DAE メッシュとしては黒色になってしまって金属的な表現にはなりませんでした.

今回筆者の調べた範囲においては glTF(ジー”エル”ティーエフ) 形式とそのバイナリ形式の glb 形式が 3D モデルのファイル内に金属やガラスなどのマテリアル表現の情報も含まれる形式とのことでしたので Rhioceros にこれらの形式をエクスポートするプラグインを導入し,丸ボタンに金属マテリアルを適用したものを glb 形式でエクスポートして,Web にある glTF ビューア で表示してみたものが次の図です.

ボタンの部分が金属的な表現になっているように見えます.

ではこの glTF や glb 形式の 3D モデルファイルが Gazebo や MoveIt で使えるのか,といったところが ROS ユーザとしては気になるところです.Gazebo や MoveIt はレンダリングエンジンに OGRE(Object-Oriented Graphics Rendering Engine) を利用しています.

OGRE の現時点で最新リリースが 2022年2月9日 リリースの 13.3 です.OGRE v13.3 では glTF2.0 形式の情報を利用した金属や布などのマテリアル表現が可能になったとのことです.

Gazebo や MoveIt でも OGRE で新しくリリースされた豊かなマテリアル表現機能を使えるように実装が進んだら,今回上手くいかなかった金属表現もできるようになるのかな?と期待しています.

色別 STL メッシュデータのエクスポート

Gazebo シミュレーションモデルの SDF ファイルから表示用(visual)メッシュを色付きで使うためには色ごとにメッシュを分けた STL データファイルに対して SDF ファイル内で色情報を指定する必要があります.

そのために Rhinoceros からは色ごとにオブジェクトを選択して各色の STL ファイルとしてエクスポートします.

一般的な STL ファイルには色情報が含まれませんので Rhinoceros 上で色を付ける必要性はないのですが,前の項目で既に色ごとに分けて色付けしたオブジェクトがありますので,ここでは「色で選択(SelColor)」でそれぞれの色を選択して「選択オブジェクトをエクスポート(Export)」すると楽にできます.

  • 色で選択
    • メニュー: 編集(E) > オブジェクトを選択(S) > 色で選択(C)
    • コマンド: SelColor

STL エクスポート自体のの手順は先ほどの「干渉チェック(collision)用 STL メッシュデータのエクスポート」内で行った手順と基本的には同じですが,色分けした,ソリッド(=閉じたポリサーフェス)ではない,開いたポリサーフェスやサーフェスをエクスポートすることが出てきますので,その場合は「STLエクスポートオプション」にて「開いたオブジェクトをエクスポート(E)」のチェックを入れる必要があります.

ファイル名はメッシュモデルの乗るシミュレーションモデルのリンク名に色名を足しておくと分かりやすいので,今回は下のリストの各ファイル名で 4色分 4つのファイルとしてエクスポートしました.

  • base_link_gray-white.stl
  • base_link_light-gray.stl
  • base_link_dark-gray.stl
  • base_link_blue-gray.stl

複数に分けた STL ファイルを MeshLab にインポートすると MeshLab 内のレイヤとして表示されるのでレイヤの表示・非表示を切り替えるなどしてメッシュの確認を行うと良いのではないかと思います.

今回の記事はここまでです.


本シリーズ次回の記事は

「Gazebo/MoveIt のための 3D モデリング(12)Gazebo や MoveIt の静モデルの作成」

として,今回エクスポートしたメッシュデータファイルを Gazebo や MoveIt のモデルファイルに組み込んで表示する様子を紹介する予定です.

著者:yamamoto.yosuke

Gazebo/MoveIt のための 3D モデリング(3)基本形状編 – その1

前回の Gazebo/MoveIt のための 3D モデリング(2)準備編 で右の図のように三面図を空間上に配置してモデリングの準備を行いました.

今回から実際のモデリング方法の紹介を行います.今回のゴールは基本的な形状で構成された次の図の状態です.

直方体と球面でモデリングします.

レイヤ03 を model という名前にしてこのレイヤ内でモデルを作成します.

レイヤ model をダブルクリックするとチェックマークが model レイヤに付いて編集対象のレイヤになります.

直方体

三面図を見るとボディの上面や側面,1段上がった底面,背面から1つ前方の面は平面で構成されているようです.(筆者が基のモデルを作成しているので自作自演なのですが…)

直方体を描画してそれらのサーフェスとします.

まず,準備で描画した outline のボックスを利用して直方体を描画するために Osnap の「端点」のチェックを入れておきます.

直方体は Box コマンドかメニューから ソリッド(O) > 直方体(B) > 2コーナー,高さ指定(C) を選択して描画します.

outline の底面の対角点の2点と高さとして上面のいずれかの角の点を順次クリックすると右の図のように直方体が描画できます.

次に,1方向のみのスケーリング Scale1D( 変形(T) > スケール(S) > 1Dスケール(1) )を使ってボディの底面の位置と奥行方向の2つの寸法調整をします.

底面の位置は Scale1D で上面位置を基準として変形を行います.

奥行方向の寸法調整は後で前面のサーフェスを作成してそれでトリムをしたいので少し前に出しておきます.もしくは背面の突出している部分の基となる面がが 40mm 分前に来るのでガムボール移動で X方向 に 40mm 移動するようにしても大丈夫です.

前面のサーフェス(球面)

洗濯機前面の主なサーフェスは球面ぽい感じがします.(自作自演ですが…)

まずは球面の半径を推定します.

洗濯機の側面視,Rhinoceros での Back ビューにて外形カーブに沿って3点指定の円を描画しておおよその半径を見てみます.

3点指定の円はメニューからは 曲線(C) > 円(C) > 3点指定(3) で実行し,コマンドでは Circle を実行してから 3点(O) を指定します.アイコンからは円形状から3点付いた円を選択します.

洗濯機前面の側面視への投影輪郭線上の3点を指定して円を描画します.

次に描画した円の半径を調べます.メニューからは 解析(A) > 半径(R) を選択し,コマンドの場合は Radius を入力して描画した円を選択します.その結果,先程描画した円の半径は「5182.7590331 ミリメートル」と解析されました.

切りの良い数字で半径は 5000mm ぐらいかな?と当たりをつけて球を描画してみます.

描画した円を削除します.

先程と同じメニュー・コマンドの「3点指定の円」を利用しますが今度は投影輪郭線上の2点と半径 5000mm を指定して描画します.

描画した半径 5000mm の円の中心から半径 5000mm の球を作成します.Osnap の「中心点」にチェックを入れます.球を作成するにはコマンドでは Sphere,メニューからは ソリッド(S) > 球(S)です.球の中心に円の中心を選択して半径 5000mm を指定して球を作成します.

このように側面視では半径 5000mm の球であるとみなしましたが,他の投影図で見ても洗濯機前面のサーフェスとしてこの半径 5000mm の球面が妥当であるか? を見てみます.

上面視(Rhinoceros の Top ビュー)から見ても半径 5000mm から作られる形状が三面図と整合するかを確認します.

作成した球を上面の高さでトリムします.上面高さで水平な直線を描画してそれを用いてトリムします.

側面視で Line コマンドかメニュー 曲線(C) > 直線(L) > 線 もしくはアイコン選択で直線描画を開始し,Osnap の「端点」にチェックが入っている状態で上面の1つの頂点を選択して Shift キーを押しながら水平に直線を描画します.

トリムに用いる直線を選択した状態でキーボードショートカット Ctrl+T を選択するとトリムコマンドが開始されますのでトリム対象として球のサーフェスを選択します.この時トリム設定として ( 切断線を延長(E)=はい 仮想交差(A)=はい ) として実行します.

  • トリム
    • キーボードショートカット: Ctrl+T
    • コマンド: Trim
    • メニュー: 編集(E) > トリム(M)

次の図は洗濯機の上面高さでトリムした球面サーフェスの上端エッジの円とその上端エッジを曲線として複製( DupEdge )してその曲線を洗濯機の上面図上の曲線とほぼ重なる場所にオフセット( Offset )させた比較です.

  1. DupEdge : メニューからは 曲線(C) > オブジェクトから曲線を作成(F) > エッジを複製(E)
  2. Offset : メニューからは 曲線(C) > オフセット(O) > 曲線をオフセット(O)
    • → コマンド内の指定で 通過点指定(T)

(画像クリックで拡大) オフセットさせた曲線は洗濯機上面図の曲線と比べて少し半径の大きい円のようですので,実際の洗濯機の前面の球面の半径は 5000mm よりも小さい可能性が高いです.

洗濯機前面を球面とした場合は 5000mm では少し半径が大きいようですので,半径 4000mm の球面として半径 5000mm で行ったのと同じように描画して評価する手順を再び行います.

  1. 側面視で洗濯機前面の投影輪郭線上の2点と半径 4000mm を指定して円を描画
  2. 描画した半径 4000mm の円の中心に半径 4000mm の球を作成
  3. 半径 4000mm の球面を洗濯機上面の高さでトリム
  4. 上面視でトリムした球面エッジからオフセットカーブを洗濯機上面図の曲線にほぼ一致する位置に描画
  5. オフセットカーブの曲率などから妥当なサーフェスか否かを判断

洗濯機前面サーフェスを半径 4000mm の球面とした場合の洗濯機上面図とトリムされた球面エッジを比較したのが次の図です.

画像では「上端エッジからオフセットした曲線(円)」が黄色になっているので少し見づらいかもしれませんが洗濯機の上面図内の曲線と一致しているように見えます.(画像クリックで拡大) このことより洗濯機前面のサーフェスを半径 4000mm の球面としたのはおおよそ妥当だと判断しました.

Perspective ビューで少し広めにモデリング空間を表示させたのが次の図です.ボックスと上面高さでトリムされた球面が見えています.

側面視で描画した円は オブジェクトを非表示( メニュー: 編集(E) > 表示(V) > 非表示(H) / コマンド: Hide ) にしてしまっても良いかもしれません.

球面とボックスを互いにトリムして洗濯機のボディ形状に近づけます.

ボックスを球面サーフェスでトリム

球面サーフェスをボックスでトリム

互いに完全に交差した球面サーフェスと Box サーフェスを互いにトリムしたので両者間に隙間はないはずです.ただ,これらは結合(Join)して一体化していないので,状態としては隙間なく互いにただ並べられている状態,英語では Watertight(水密)などと言われる状態です.
それを確認するために解析ツールで「エッジを表示」してみます.

  • エッジを表示
    • メニュー: 解析(A) > エッジツール(E) > エッジを表示(E)
    • コマンド: ShowEdges

エッジ分析の小ウィンドウが表示されたらその中の 表示 – オープンエッジ(N) を選択します.
トリムされた球面サーフェスと Box サーフェスの境界部分が明るい紫からピンクのような色で表示されると思います.

トリムした球面サーフェスと Box サーフェスを結合(Join)してオブジェクトとして1体化ます.両方のサーフェスを選択してから結合を実行します.

  • 結合
    • メニュー: 編集(E) > 結合(J)
    • コマンド: Join
    • キーボードショートカット: Ctrl+J

結合したら再び「エッジを表示」を実行してオープンエッジがないかを確認します.
オープンエッジがなかったら次のようなエッジ分析の結果が出るかと思います.

合計??個のエッジ.オープンエッジ,非多様体エッジはありません.

これは 「閉じたポリサーフェス」 や 「ソリッド」 と呼ばれるモデルの状態を意味します.

今後「ソリッドモデル」や「閉じたポリサーフェス」であるはずのモデルを作った場合は都度確認するようにしましょう.都度確認しないで何かのはずみで僅かな隙間が残っているまま作業を進めてしまうと後々にサーフェスが閉じなくなり多くの作業をやり直さないとならなくなってしまうことがあります.

  • Tips
    • 「ソリッドモデル(閉じたポリサーフェス)」 モデルにしておくと Gazebo や MoveIt だけではなく有限要素解析による応力計算や数値流体解析などにも応用することができます.

次に前面下部のサーフェスも似たような面であろうと目論んで,側面視(Rhinoceros の Back ビュー)で半径 4000mm の円を描画してみると,大体 Z=350mm ぐらいの平面で上下反転しているように見えます.

球面サーフェスを反転コピーするために先程結合したソリッド(閉じたポリサーフェス)モデルから 「サーフェスを抽出」 して球面サーフェスを分離します.

  • サーフェスの抽出
    • メニュー: ソリッド(O) > サーフェスを抽出(A)
    • コマンド: ExtractSrf

球面サーフェスを反転コピーするために側面視(Rhinoceros の Back ビュー)で直線(Line)を座標 (0,350) から水平に引きます.

前面の球面サーフェスを選択してミラー変形で反転コピーします.

  • ミラー
    • メニュー: 変形(T) > ミラー(I)
    • コマンド: Mirror

座標 (0,350) から水平に引いた線の両端を順に選択して反転させます.

座標 (0,350) から水平に引いた線で不要になる球面サーフェスをトリムし,またミラーコピーした球面サーフェスの Box サーフェスからはみ出る部分や Box サーフェスのはみ出る部分を球面サーフェスでトリムします.

これらのトリムされた上下の球面サーフェスと Box サーフェスを結合(Join)すると次のようなソリッド(閉じたポリサーフェス)モデルになり,記事の冒頭で述べたゴールに辿り着きました.

次回は, 「3D モデリング(4)基本形状編 – その2」 として洗濯機の背面や底部の形状のモデリングを説明する予定です.