タグアーカイブ CAD

著者: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 モデリング(5)滑らかなサーフェス – 知識編

前回 「Gazebo/MoveIt のための 3D モデリング(3)基本形状編 – その2」 では洗濯機の基本的な形状で構成されるサーフェスのモデリングを行いました.

今回は発展的な内容として滑らかなサーフェスのモデリングに向けた予備知識的な内容の説明をします.

ロボットモデルはシミュレータ上で使うために結局メッシュ(ポリゴン)にしてしまうのでシミュレーションなどに利用する 3D モデル作成においては 「滑らかなサーフェス」 である必要性は高くありません.

しかし,モデリング対象の中には滑らかなサーフェスになるように設計されている製品もあります.そのような製品のモデリングの際に対象物の形状が円弧のように見えるけど何か違うので合わなくて悩むようなことがあります.そういったときに円弧などの基本的な形状以外のサーフェスもあることを知っていると,それは厳密には合わないものとして割り切って近似的に円弧などのシンプルな形状としてモデリングするということも適切に判断できると思います.

このようなことから,今回の記事はそういった 「滑らかなサーフェス」 について 「知る」 ことを目的としています.

「滑らか」とは?

「滑らか」 とはは何であるかというと,曲線やサーフェスの位置や接線方向,曲率,曲率の変化率に連続性があるということです.

上の図は 90° の角度をもつ直線間を曲線で接続させたときの連続性の違いによる曲率(黄色カーブ)のグラフ(CurvatureGraph)を表した画像をアニメーション化したものです.
(クリックで拡大)

各接続条件は次のリストのように連続性の条件が加わってゆくように考えてください.
「R形状」は「接線連続」のうち円弧で接続できる特殊なケースと捉えることができます.

  1. 位置連続
  2. 位置連続 + 接線連続
  3. 位置連続 + 接線連続 + 曲率連続
  4. 位置連続 + 接線連続 + 曲率連続 + 曲率変化率連続
  5. 位置連続 + 接線連続 + 曲率連続 + 曲率変化率連続 + 曲率変化率の変化率連続

上の図の接続連続性の異なる曲線を 「押し出し」 してサーフェスを作成してレンダリング表示にしたものが次の図です.

影の付き方が曲率や曲率変化率などの連続条件を加えてゆくと段々と滑らかになるのが見て取れるでしょうか?

サーフェスの曲率を解析して色で表した(CurvatureAnalysis)ものが次の図で,青が曲率が小さく,赤が曲率が大きいコンタ図になっています.

連続性の条件が加わるにつれて接続部周辺の曲率の変化が緩やかになっています.

また,サーフェスの滑らかさを評価するために 「ゼブラ(縞模様・Zebra)」 解析もわかりやすいのでよく利用します.

ゼブラ表示によりサーフェスの連続性がより強調されます.縞模様の通り方の滑らかさがサーフェスの接続性の滑らかさを表しています.サーフェスが滑らかに接続しているかどうかを評価したり,接続を滑らかに修正する際に役立ちます.

本シリーズの記事のモデリング対象として作成した洗濯機モデルの曲率とゼブラを表示したものが次の2つの図です.モデル全体で解析すると解析用のメッシュを細かく出来なくなるので,実際には接続性を評価する面に限って解析用メッシュをなるべく細かくして解析をするようにしています.

「制御点」と「次数」

実際に滑らかなサーフェスをモデリングする場合は,サーフェスが CAD やサーフェスモデラ内部でどのように表現されているかを理解しているとより意図したものに近いサーフェスを作成できるように思います.

Rhinoceros や一般的な CAD などでは曲線やサーフェスは NURBS (Non-Uniform Rational B-Spline/非一様有理Bスプライン) という数学的モデルで表現されています.

NURBS 以外にもサーフェスの 3D 表現モデルとして SubD (Subdivision/細分割曲面) もあります. SubD はコンピュータグラフィックス系の 3D モデリングソフトウェアで利用されていますが,機構設計分野ではあまり使われていませんので本シリーズの記事の対象としません.

NURBS で表現される曲線やサーフェスが何で構成されているかは大まかに述べますと 「制御点」 と 「次数」 です.

上の図は前項目で 90° の角度をもつ直線間を連続性の異なる接続をした曲線がそれぞれどのような 「制御点」 と 「次数」 で表現されているかを示した図をアニメーション化したものです.

NURBS カーブにおいてはその接続における連続性は次のリストにある各数の「制御点」により構成されています.

  1. 位置連続 → 端点の 1 点
  2. 接線連続 → 端点を含めたの 2 点
  3. 曲率連続 → 端点を含めたの 3 点
  4. 曲率変化率連続 → 端点を含めたの 4 点
  5. 曲率変化率の変化率連続 → 端点を含めたの 5 点

「次数(degree)」 は大きな数字になるほど曲線が滑らかになります.

上の図は 90° の角度をもつ直線間を接続した 「制御点:8 次数7 の曲線(曲率変化率連続)」 をあえて 「リビルド(Rebuild)」 して 「制御点:8 次数: 3 の曲線」 にして両端点の曲率を接続先の直線に 「マッチング(Match)」 した曲線の曲率の比較です.同じ制御点数でも次数が低いと曲線内で曲率の変化率の連続性が保てなくなってしまいます.

曲線に設定できる 「次数の最大値」 は 「制御点数 – 1」 です.

両端を曲率連続にするための 「制御点が6個」 の曲線の場合は 「次数の最大値は5次」,両端を曲率変化率連続にするための 「制御点が8個」 の場合は設定できる 「次数の最大値は7次」 になります.

制御点が多いとより細かく曲線やサーフェスの形状の制御が出来ますが,編集が大変だったり,データサイズが大きくなってしまうので,最小の制御点と適切な次数で表現したい形状や滑らかさを規定できるのがベストです.

接続条件は曲線の両端で同じである必要はないので,例えば片方の端は 「位置連続」 にして,もう片方の端は 「曲率変化率連続」 にするということも可能です.この場合の必要最小限の制御点は 「位置連続側: 1点」 と 「曲率変化率連続側: 4点」 と合わせて 「5点」 は必要になります.制御点を 「5点」 とした場合の次数の最大値を採って 「4次」 とするのが良いでしょう.

制御点が少なくて意図する形状が得られないようでしたら適宜制御点を多くして,次数もそれに合わせて大きくすると良いですが,次数の方は最大でも 「7次」 で十分なように筆者は考えています.

サーフェスにおける「制御点」と「次数」

これまで曲線を例に 「制御点」 と 「次数」 について説明してきましたが,サーフェスは曲線の「制御点」と「次数」を2方向に拡張したものです.

サーフェスは 「U方向」 と 「V方向」 の2方向がある 「四角い布」 をベースに,それを伸縮・曲げを行ったり,トリムしてその一部を使ったりするイメージとして捉えることができます.

円錐体のような三角形のサーフェスもありますが 「四角い布」 の特殊例と捉えることができ,同様にUV方向それぞれの要素があります.

次の図は本シリーズでモデリング対象とするために作成した洗濯機モデルのボディの角部のサーフェスの制御点と曲率のグラフを表示したものです.四方にある接続先のサーフェスとそれぞれ(なるべく)曲率変化率まで連続するように作成しました.そのため次数を 7次 とし,制御点を U方向に 15点,V方向に 8点 を持つサーフェスとしました.

  • 図示したサーフェス例の制御点と次数
    • U方向: 制御点 15点 / 次数 7
    • V方向: 制御点 8点 / 次数 7

曲線の連続性と同じように,サーフェスの連続性も各辺毎に作成時設定できるサーフェスもありますし,マッチングの際に異なる設定で各辺で行えば可能ですが,四辺の接続先と矛盾がないようにしないと隙間のないサーフェスにならない可能性もある点が曲線に比べて難しいところです.

どれほど滑らかにする?

さて,ロボットシミュレータのための 3D モデリングにおいてはどれほど滑らかなサーフェスを作成したら良いのでしょうか?

本記事冒頭で述べたように,ロボットモデルはシミュレータ上で使うために結局メッシュ(ポリゴン)にしてしまうのでシミュレーションなどに利用する 3D モデル作成においては 「滑らかなサーフェス」 である必要性は高くありません.

曲率連続や曲率変化率連続のサーフェスでモデリングしてメッシュ化してもそのような連続性に近い状態を維持しようとするとメッシュが細かくなりデータが重くなります.ただ,そのロボットシミュレーションをデモンストレーションやプレゼンテーションで綺麗に見せたく,少しメッシュデータが重くても良いような場合はなるべく滑らかなサーフェスをモデリングすることもあるように思います.

また,メッシュのデータ量の他にモデル作成の手間も考えておくべきでしょう.

下のリストにサーフェスの連続性の違いをまとめました.技術的なロボットシミュレーションが目的であれば 接線連続 までとしてモデリング時間を省くのも1つの方法です.大きな面はメッシュで形状が潰れてしまわないので 曲率連続 や 曲率変化率連続 まで考慮したモデルとして,小さな面はメッシュ形状に埋もれてしまうので R形状 や 接線連続 としてメリハリをつけるのも良いでしょう.

Rhinoceros では「曲率連続」までは標準の機能として普通に利用できるのでロボットシミュレータのための 3D モデリングでも用いるのはそんなに手間のかかることではないように思います.

  1. 位置連続
    • 面取り形状など
    • 機械設計的
  2. R形状
    • 隅R・角Rや.前回の記事で作成したフィレットのロフトなどが例
    • フライスや旋盤で機械加工された対象物のモデリングには必須
    • 機械設計的
  3. 接線連続
    • ロボット 3D モデリングの自由曲面では多く使う場合が多いか?
  4. 曲率連続
    • 滑らかに見えるサーフェス
    • デザイン的
    • 使っている CAD やサーフェイスモデラで機能的に簡単に作成できるようだったら用いてみるのもあり
    • Rhinoceros では
      • 標準で曲率連続にサーフェフをマッチング修正する機能がある
  5. 曲率変化率連続
    • より滑らかに見えるサーフェス
    • ロボット 3D モデリングでは知識として持っていたら十分
    • 使えると造形できるものが増える
    • デザイン的
    • Rhinoceros では
      • 「作成時」に曲率変化率連続性のある曲線・サーフェスを作成する機能はある
      • 「修正時」は曲率連続マッチング機能を利用した後に,加えて曲率目視で4番目の制御各点を手動調整する必要があるので手間
        • (この曲率変化率連続マッチングを行う Plug-in があれば筆者にも教えて欲しい!)
  6. 曲率変化率の変化率連続
    • Rhinoceros では
      • 「作成時」に曲率変化率の変化率連続性のある曲線・サーフェスを作成する機能はある
      • 「修正時」に曲率目視で5番目の制御点まで手動調整するのは難しいか?

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

大体どのような滑らかさのサーフェスの種類があって,CAD やサーフェスモデラでそれを作成するために必要な条件や作成の手間のイメージが伝わっていると良いのですが.


本シリーズ次回の記事は

「Gazebo/MoveIt のための 3D モデリング(6)滑らかなサーフェス – 作成編」

を予定しています.