このページでは物理シミュレータV-REP上で動作する上で動作するRTCを作成して、以下のようにPython版サンプルコンポーネントのジョイスティックコンポーネントと接続して車体を操作するシステムの作成を行います。
以下からV-REPのインストーラーを入手してインストールしてください。
V-REPをインストールしたフォルダ(C:\Program Files\V-REP3、もしくは任意ディレクトリのV-REP_PRO_EDU_V3_5_0_Linux)にOpenRTM Lua版の各ファイルをコピーします。
以下から64bit用のOpenRTM Lua版ファイル一式(OpenRTM Lua x.y.z Lua5.1 64bit)をダウンロードしてください。
OpenRTM Lua版からV-REPにファイルをコピーします。
openrtm-lua-x.y.z-x64-lua5.1\lua\以下のファイルを全てC:\Program Files\V-REP3\V-REP_PRO_EDU\lua\以下にコピーしてください。
Ubuntuの場合は任意ディレクトリのV-REP_PRO_EDU_V3_5_0_Linux以下にコピーします。

※CoppeliaSim、もしくはV-REPの新しいバージョンの場合はidlフォルダを一階層上のディレクトリ(C:\Program Files\V-REP3\V-REP_PRO_EDU、もしくはV-REP_PRO_EDU_V3_5_0_Linux)にコピーする必要があります。

以下、WindowsとUbuntuでコピーするファイルが違います。Ubuntuで使いたいという奇特な人は注意してください。
openrtm-lua-x.y.z-x64-lua5.1\clibs\以下のファイルを全てC:\Program Files\V-REP3\V-REP_PRO_EDU\以下にコピーしてください。

以下からluamodule_linuxを入手してください。
中身のファイルを全てV-REP3\V-REP_PRO_EDU\以下にコピーしてください。

RTC BuilderによるRTCの基本的な作成手順は以下のページを参考にしてください。
上のページの作成手順に従って、以下の仕様のRTCを作成してください。
| モジュール名 | VRepSample |
onExecuteを有効にしてください。
| ポート名 | in |
| データ型 | RTC::TimedFloatSeq |
ソースコードの先頭付近に以下の行を追加して、シミュレーションのスレッドと自動的に切り替える機能をオフにしてください。
機能をオフにした場合、simSwitchThread関数によりシミュレーションを進める必要があります。
simSetThreadAutomaticSwitch(false)
onExecute関数を以下のように編集してください。
function obj:onExecute(ec_id)
simSwitchThread()
if self._inIn:isNew() then
local data = self._inIn:read()
local joint_front_left_wheel=simGetObjectHandle('joint_front_left_wheel')
local joint_front_right_wheel=simGetObjectHandle('joint_front_right_wheel')
local joint_back_right_wheel=simGetObjectHandle('joint_back_right_wheel')
local joint_back_left_wheel=simGetObjectHandle('joint_back_left_wheel')
simSetJointTargetVelocity(joint_front_left_wheel, data.data[2]/50+data.data[1]/50)
simSetJointTargetVelocity(joint_front_right_wheel, -data.data[2]/50+data.data[1]/50)
simSetJointTargetVelocity(joint_back_right_wheel, -data.data[2]/50+data.data[1]/50)
simSetJointTargetVelocity(joint_back_left_wheel, data.data[2]/50+data.data[1]/50)
end
return self._ReturnCode_t.RTC_OK
end
simSwitchThread関数によりシミュレーションを1ステップ進めています。
InPortで読み込んだデータを車輪の速度に入力しています。
V-REPの関数については以下のページが参考になります。
事前にネームサーバーの起動が必要です。
※OpenRTM-aist 1.2以降ではRT System Editorにネームサーバー起動ボタンがあるため、手順が簡単になっています。
TkJoyStickコンポーネントを入手して、TkJoyStickComp.exeを実行してください。
robots->mobile->Robotnik_Summit_XL140701.ttmをドラックアンドドロップして配置します。
new scene(scene1)のツリーからRobotnik_Summit_XLの名前の右にあるアイコンをクリックするとLuaスクリプトの編集ウインドウが起動します。
その上に先ほど作成したVRepSample.luaのソースコードを全て上書きしてください。

V-REP上で以下のボタンを押すとシミュレーションが開始してRTCが起動します。

まずRTCの起動に成功している場合は、以下のようにネームサービスビューにRTCが表示されます。

Open New System Editorボタンを押してシステムダイアグラムを表示してください。

ネームサービスビューからシステムダイアグラムにRTCをドラックアンドドロップしてください。

TkJoyStick0のposのOutPortを、VRepSample0のinのInPortにドラックアンドドロップしてください。 これで通信ができるようになります。

All Activateボタンを押すとTkJoyStick0からデータが送信されるため操作ができるようになります。

VRepSample.luaのmanager:init関数の引数を以下のように変更してください。
manager:init({"-o", "manager.components.preconnect:VRepSample0.in?port=rtcname://localhost/TkJoyStick0.pos", "-o", "manager.components.preactivation:VRepSample0,rtcname://localhost/TkJoyStick0"})
-oオプションでパラメータの設定ができます。
"-o", "manager.components.preconnect:VRepSample0.in?port=rtcname://localhost/TkJoyStick0.pos"起動時に接続するポートを指定します。 この場合はVRepSample0というRTCのinというデータポートを、TkJoyStick0というRTCのposというポートに接続します。
ただし、TkJoyStick0は別プロセスで起動しているため、rtcname形式による指定が必要になります。 rtcname形式はネームサーバーからRTCを取得する方法です。rtcname://アドレス/RTC名.ポート名で指定します。
"-o","manager.components.preactivation:VRepSample0,rtcname://localhost/TkJoyStick0"起動時にアクティブ化するRTCを指定します。
coppeliaSim.exe、もしくはvrep.exeと同じフォルダのrtc.confを読み込みます。