タグアーカイブ Rhinoceros

著者: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 モデリング(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 モデリング(6)滑らかなサーフェス – 作成編(その1)

前回 「Gazebo/MoveIt のための 3D モデリング(5)滑らかなサーフェス – 知識編」 では 3D モデリングにおける滑らかなサーフェスとは何かについて曲率などの連続性や CAD やサーフェスモデラ内での形状表現のされ方について説明しました.

今回は前回の記事の知識を踏まえて滑らかなサーフェスの作成例について説明します.

滑らかなサーフェスは Gazebo や MoveIt のモデルを作成する場合においてはあまり重要性は高くない… と前回の記事を書いた時点では考えていましたが,今後,Gazebo や MoveIt を走らせる PC の CPU / GPU 性能が向上して細密メッシュモデルを使った精密なシミュレーションへの要求も段々と高くなるかもしれない,とも思いました.

洗濯機前面上部の操作ボタン

サーフェスはモデル内で大きいものから順に作成していった方が全体のバランスを確認しながら作業を進められて修正作業が必要になる量も少なくなるので良いと思います.

ただ,本記事ではまず,Rhinoceros に備わっているコマンド1つほどであまり制御点とか次数とか細かく意識しなくても作成できる曲率連続の滑らかなサーフェスの例として小さいサーフェスの洗濯機前面上部の操作ボタンのモデリングについて説明します.

四角いボタンのモデリング

洗濯機の前面視( Rhinoceros の Right ビュー )で四角いボタンの大きさを見ると大体 20mm 角でした.

ボタンを1つモデリングして,それを洗濯機前面のサーフェス上に8つコピーして配置します.

左の図は四角いボタンのソリッドモデルの作成過程をアニメーション化した画像です.

各手順を以下に順を追って説明します.

20mm の正方形の線を選択して「テーパで平面曲線を押し出し(ExtrudeCrvTapered)」 を実行し,ドラフト角度 15° の設定で 3mm 押し出します.

  • テーパで平面曲線を押し出し
    • メニュー: ソリッド(O) > 平面曲線を押し出し(X) > テーパ(T)
    • コマンド: ExtrudeCrvTapered

四隅を「曲率連続」で丸めるために「エッジをブレンド(BlendEdge)」を実行して四隅のエッジを選択します.

デフォルトでは半径が 1mm となっていてモデリングしたい四隅の半径はもう少し大きいので洗濯機前面図と比較しながら寸法を調整します.

  • エッジをブレンド
    • メニュー: ソリッド(O) > エッジをフィレット(F) > エッジをブレンド(B)
    • コマンド: BlendEdge

「エッジをブレンド」コマンド内の設定を次のようにして

  • ハンドルを連動(L)=はい
  • レールタイプ(R)=レール間の距離(I)

次にコマンド内設定で「全てを設定(T)」で半径(上記設定の場合はレール間の距離)を 8mm にしてコマンドを確定します.

「エッジをブレンド」コマンド内の「レールタイプ」の設定は「レール間の距離」にした場合が比較的綺麗なフィレットがかかるように思っているので設定しました.フィレットをかけるサーフェスの組み合わせによって他の設定の方が良い場合もあるので各モデリング対象にて適宜選択してください.

今度は指で押す面の周囲にブレンドエッジを作成します.「エッジをブレンド(BlendEdge)」コマンドを実行してコマンド内設定 「次の半径(R)」 を 2mm に設定してから該当するエッジをすべて選択して確定・実行します.

下の図は「エッジのブレンド」でフィレットを作成した四角いボタンの平均曲率解析とゼブラ解析の表示結果です.

これらのブレンドエッジは数ミリと小さいので問題にはあまりなりませんが,大きなサーフェスとしてブレンドエッジを作成する場合は応用的に次のリストの項目を調整編集すると良いでしょう.

  • ブレンドエッジ関連で応用的な項目
      • BlendEdge だとフィレット接続する方向は 5次-6点 で「曲率連続」になるが,長手方向は 3次-多点 になってしまいガタつく
        • →「次数を変更(ChangeDegree)」で長手方向の次数を 7次 に変更してサーフェスマッチングを行い再接続する
        • → 制御点が多すぎる場合は RebuildUV コマンドで U方向 のみ制御点を少なくしてリビルドして(この時点ではまだ 3次-多点 ),その後で「次数を変更(ChangeDegree)」で U方向を 7次 に変更してサーフェスマッチング(MatchSurf)
      • テーパ押し出しの基となった正方形も各辺直線ではなく少し外に膨らむ緩い円弧にするとより滑らかな感じになる

四角いボタンのモデルができましたので洗濯機前面のサーフェス上にコピーして配置します.

ボタンの押される方向の軸と洗濯機前面のサーフェスの法線軸を合わせ,かつ上下辺を水平に配置したいので「配置(3点指定)・(Orient3Pt)」を利用してコピーします.「 配置(3点指定)」は下記リストの 3点 を移動元と移動先で指定して配置変換するものです.

  1. 移動原点
  2. 移動原点から第1の方向を決める方向上の点
  3. 移動原点と第1方向点で構成される軸回りの方向を決める点

四角いボタンの移動先とするために配置するサーフェス上の法線方向と接線方向の直線を各配置点で描画します.まず,YZ 平面上に四角いボタンを配置する中心線を描画して,洗濯機前面視(Rinoceros の Right ビュー)にてそれらをサーフェスに「投影(Project)」します.

  • 投影
    • メニュー: 曲線(C) > オブジェクトから曲線を作成(F) > 投影(P)
    • コマンド: Project

「直線(Line)」を実行してコマンド内で「法線(N)」を指定,もしくはメニューから「サーフェス法線(U)」を実行して,サーフェスを選択後,サーフェス上にある投影した中心曲線の交点を選択して法線を描画します.

今回の「配置(3点指定)・(Orient3Pt)」ではスケーリングコピーはしないので長さは適当で大丈夫です.順次各点における法線を描画して合計8軸を準備します.

  • サーフェス法線
    • メニュー: 曲線(C) > 直線(L) > サーフェス法線(U)
    • コマンド: Line → 法線(N) を選択

洗濯機前面の球面サーフェスに食い込む形で四角いボタンを配置したいのでコピー元となる点を 1mm ボタンの高さ方向へ移動しておいてから「配置(3点指定)・(Orient3Pt)」でコピー元,コピー先の各3点を指定してボタンをサーフェス上に配置します.

  • 配置(3点指定)
    • メニュー: 変形(T) > 配置(O) > 3点指定(3)
    • コマンド: Orient3Pt

コピー元の3点指定
コピー先サーフェス上のの3点指定

8つの四角いボタンを洗濯機前面のサーフェス上に配置してゴースト表示とレンダリング表示をしてそれぞれキャプチャしたものが次の2つの画像です.

丸いボタンのモデリング

丸いボタンの直径は大体 50mm ぐらいのようです.

丸いボタンのように軸回転形状のものは回転形状のプロファイル曲線を作成してそれを軸回りに回転してソリッドモデル(閉じたポリサーフェス)とするのが一番簡単だと思います.

丸いボタンモデルの作成自体は上記四角いボタンのように作成しやすい場所で作成して,軸回りの形状は軸対称で同じなのでそれを今度は「配置(2点指定)・(Orient)」でコピー移動して洗濯機上のサーフェスに配置します.

丸いボタンのモデリングと配置の作業手順をまとめると次のようになります.

  1. 回転中心軸を含む平面上に回転形状プロファイル曲線を描画
  2. 回転中心軸回りに「回転(Revolve)」にて1周分のサーフェスを作成
  3. 作成されたサーフェス群を「結合(Join)」してソリッド(閉じたポリサーフェス)にする
  4. 丸ボタンモデルのコピー元原点とコピー先の原点と方向(サーフェス法線方向)を描画
  5. 「配置(2点指定)・(Orient)」でコピー移動

回転方向は曲率一定になるので回転プロファイルの曲線さえ滑らかな曲線を作成すれば回転で作成するポリサーフェスも滑らかになります.そこで丸ボタンの回転プロファイルを次の図のように作成するのですが,ボタンの側面と指で押される面に相当する曲線間に滑らかなフィレット曲線を作成します.

ボタンの側面と指で押される面に相当する両曲線に接する円を描画して円の接する点でトリムするとその間の曲線の接続も比較的バランス良く繋がります.円との接点でトリムされた両曲線間に「接続(BlendCrv)」で曲線を作成します.

  • 接続
    • メニュー: 曲線(C) > 接続(U)
    • コマンド: BlendCrv

「接続(BlendCrv)」内の設定で各接続点における接続条件を設定します.連続性を「曲率」もしくは「G3(曲率変化率)」を設定すると各設定に応じた滑らかな曲線が描画されます.各制御点は [ Shift ] キーを押しながらマウスでドラッグすると対象な点も同時に移動してくれるので便利です.曲線形状や曲率変化を見ながら制御点を調整して意図した形状で確定をします.

回転形状のプロファイル曲線が作成できたら「回転(Revolve)」 で曲線を回転したサーフェスを作成します.

  • 回転
    • メニュー: サーフェス(S) > 回転(V)
    • コマンド: Revolve

1回転分のサーフェスを作成するにはコマンド内で「360度(F)」を指定します.

右の図(ワイヤーフレーム表示)のようなボタン形状のサーフェスが作成されます.

1回転分作成したサーフェスをすべて選択して「結合(Join・Ctrl-J)」してソリッドモデル(閉じたポリサーフェス)にします.

<参考>
Rhinoceros 上では回転形状プロファイル曲線群を先に「結合(Join)」してから「回転(Revolve)」しても同じ形状になるのですが,サーフェスのフィレットのような回り込みの大きい形状と一体化したサーフェスをメッシュ化するときにフィレット形状付近を飛ばして粗いメッシュが作成されてしまうことがあります.フィレット形状部分のサーフェスは一体化したものとせずに別体のものを作成した後「結合(Join)」した方がフィレットサーフェスのエッジがメッシュ境界に反映されるので適切な形状のメッシュ作成のためには良いでしょう.

丸いボタンのソリッドモデルが作成できたら「配置(2点指定)・(Orient)」で洗濯機前面サーフェス上の法線方向に合わせてコピー移動します.先述したように軸回りの形状は軸対称で同じなので位置と方向1つのみの指定の移動変換をします.

四角いボタンと同様に前面サーフェスに少し食い込ませたいので丸いボタンの背面から 1mm 入ったところをコピー原点としてからボタンを押す方向軸上の1点を選択して,コピー先の洗濯機前面サーフェス上の点と法線方向を指定してスケーリングしない設定でコピー移動します.

  • 配置(2点指定)
    • メニュー: 変形(T) > 配置(O) > 2点指定(2)
    • コマンド: Orient

丸いボタンを洗濯機前面サーフェス上に配置したものを四角いボタンと併せて Perspective ビューにゴースト表示させたものが次の図です.

レンダリング表示にしてキャプチャした画像が次の図です.

洗濯機本体とボタン類のソリッドモデルをブーリアン演算して一体化するのは全ての作業の最後で良いので,他のモデリング作業の邪魔にならないようにとりあえず新しいレイヤー buttons(例)を追加してそこに移動しておきます.

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


本シリーズ次回の記事は引き続き滑らかなサーフェスの作例紹介で

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

を予定しています.

著者: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)滑らかなサーフェス – 作成編」

を予定しています.