このページでは物理シミュレータCoppeliaSim上で動作する上で動作するRTCを作成して、以下のようにPython版サンプルコンポーネントのジョイスティックコンポーネントと接続して車体を操作するシステムの作成を行います。 CoppeliaSim 4.3で動作確認しています。
以下からCoppeliaSimのインストーラーを入手してインストールしてください。
CoppeliaSimをインストールしたフォルダ(C:\Program Files\CoppeliaSim
、もしくは任意ディレクトリのCoppeliaSim_Edu_V4_3_0_Ubuntu18_04
)にOpenRTM Lua版の各ファイルをコピーします。
以下から64bit用のOpenRTM Lua版ファイル一式(OpenRTM Lua x.y.z *** Lua5.3 64bit バージョン名削除(CoppeliaSim向け))をダウンロードしてください。
OpenRTM Lua版からCoppeliaSimにファイルをコピーします。
openrtm-lua-x.y.z-cc-x64-lua5.3-versionomit\lua
フォルダをC:\Program Files\CoppeliaRobotics\CoppeliaSimEdu\
以下にコピーして上書きしてください。
Ubuntuの場合は任意ディレクトリのCoppeliaSim_Edu_V4_3_0_Ubuntu18_04
以下にコピーします。
openrtm-lua-x.y.z-cc-x64-lua5.3-versionomit\lua\idl
フォルダを(C:\Program Files\CoppeliaRobotics\CoppeliaSimEdu
、もしくはCoppeliaSim_Edu_V4_3_0_Ubuntu18_04
)にコピーします。
以下、WindowsとUbuntuでコピーするファイルが違います。Ubuntuで使いたいという人は注意してください。
openrtm-lua-x.y.z-cc-x64-lua5.3-versionomit\clibs\
以下のファイルを全てC:\Program Files\CoppeliaSim3\CoppeliaSim_PRO_EDU\luar\
以下にコピーしてください。
以下からluamodule_ubuntu_lua53
を入手してください。
中身のファイルを全てCoppeliaSim_Edu_V4_3_0_Ubuntu18_04/
以下にコピーしてください。
RTC BuilderによるRTCの基本的な作成手順は以下のページを参考にしてください。
上のページの作成手順に従って、以下の仕様のRTCを作成してください。
モジュール名 | CoppeliaSimSample |
onExecute
を有効にしてください。
ポート名 | in |
データ型 | RTC::TimedFloatSeq |
ソースコードの先頭付近に以下の行を追加して、シミュレーションのスレッドと自動的に切り替える機能をオフにしてください。
sim.setThreadAutomaticSwitch(false)
onExecute
関数を以下のように編集してください。
function obj:onExecute(ec_id)
if self._inIn:isNew() then
local data = self._inIn:read()
local joint_front_left_wheel=sim.getObjectHandle('joint_front_left_wheel')
local joint_front_right_wheel=sim.getObjectHandle('joint_front_right_wheel')
local joint_back_right_wheel=sim.getObjectHandle('joint_back_right_wheel')
local joint_back_left_wheel=sim.getObjectHandle('joint_back_left_wheel')
sim.setJointTargetVelocity(joint_front_left_wheel, data.data[2]/50+data.data[1]/50)
sim.setJointTargetVelocity(joint_front_right_wheel, -data.data[2]/50+data.data[1]/50)
sim.setJointTargetVelocity(joint_back_right_wheel, -data.data[2]/50+data.data[1]/50)
sim.setJointTargetVelocity(joint_back_left_wheel, data.data[2]/50+data.data[1]/50)
end
return self._ReturnCode_t.RTC_OK
end
InPortで読み込んだデータを車輪の速度に入力しています。
CoppeliaSimの関数については以下のページが参考になります。
Managerの起動やRTCの生成処理を初期化処理のsysCall_init
関数で呼ぶ必要があります。
またデフォルトではRTCは周期実行コンテキストを使用しますが、トリガ駆動実行コンテキスト(OpenHRPExecutionContext
)に変更します。
if openrtm.Manager.is_main() then
function sysCall_init()
local manager = openrtm.Manager
manager:init({"-o","exec_cxt.periodic.type:OpenHRPExecutionContext"})
manager:setModuleInitProc(MyModuleInit)
manager:activateManager()
manager:runManager(true)
end
Manager、RTCの更新処理をsysCall_actuation
、sysCall_sensing
関数に記述します。
これでシミュレーション更新時にManagerの更新、RTCのコールバック関数呼び出し処理が実行されます。
function sysCall_actuation()
local openrtm = require "openrtm"
local mgr = openrtm.Manager
mgr:step()
local comp = mgr:getComponent("CoppeliaSimSample0")
local ec = comp:get_owned_contexts()[1]
ec:tick()
end
Managerの終了処理をsysCall_cleanup
関数に記述することで、シミュレーション終了時にManager、RTCが終了します。
function sysCall_cleanup()
local openrtm = require "openrtm"
local mgr = openrtm.Manager
mgr:shutdown()
end
事前にネームサーバーの起動が必要です。
※OpenRTM-aist 1.2以降ではRT System Editorにネームサーバー起動ボタンがあるため、手順が簡単になっています。
TkJoyStickコンポーネントを入手して、TkJoyStickComp.exe
を実行してください。
robots
->mobile
->Robotnik_Summit_XL140701.ttm
をドラックアンドドロップして配置します。
new scene(scene1)
のツリーからRobotnik_Summit_XL
の名前の右にあるアイコンをクリックするとLuaスクリプトの編集ウインドウが起動します。
その上に先ほど作成したCoppeliaSimSample.lua
のソースコードを全て上書きしてください。
CoppeliaSim上で以下のボタンを押すとシミュレーションが開始してRTCが起動します。
まずRTCの起動に成功している場合は、以下のようにネームサービスビューにRTCが表示されます。
Open New System Editor
ボタンを押してシステムダイアグラムを表示してください。
ネームサービスビューからシステムダイアグラムにRTCをドラックアンドドロップしてください。
TkJoyStick0
のpos
のOutPortを、CoppeliaSimSample0
inのInPortにドラックアンドドロップしてください。 これで通信ができるようになります。
ここでTkJoyStick0
の実行周期を10Hz定します。デフォルトでは1000Hzですが、CoppeliaSimSample0側のデータ受信の頻度が多いとシミュレーションが遅くなるため調整します。
システムダイアグラム上のTkJoyStick0
をクリックして選択後に、Execution Context Viewタブを表示します。
その後、rate
を10
に変更後、適用
ボタンを押します。
All Activate
ボタンを押すとTkJoyStick0
からデータが送信されるため操作ができるようになります。
CoppeliaSimSample.luaのmanager:init関数の引数を以下のように変更してください。
manager:init({"-o","exec_cxt.periodic.type:OpenHRPExecutionContext",
"-o", "manager.components.preconnect:CoppeliaSimSample0.in?port=rtcname://localhost/TkJoyStick0.pos",
"-o", "manager.components.preactivation:CoppeliaSimSample0,rtcname://localhost/TkJoyStick0",})
-o
オプションでパラメータの設定ができます。
"-o", "manager.components.preconnect:CoppeliaSimSample0.in?port=rtcname://localhost/TkJoyStick0.pos"
起動時に接続するポートを指定します。 この場合はCoppeliaSimSample0
というRTCのin
というデータポートを、TkJoyStick0
というRTCのpos
というポートに接続します。
ただし、TkJoyStick0
は別プロセスで起動しているため、rtcname形式
による指定が必要になります。 rtcname形式
はネームサーバーからRTCを取得する方法です。rtcname://アドレス/RTC名.ポート名
で指定します。
"-o","manager.components.preactivation:CoppeliaSimSample0,rtcname://localhost/TkJoyStick0"
また、以下のコードを追加することでTkJoyStick0の実行周期を変更できます。
local naming = manager:getNaming()
local comps = naming:string_to_component("rtcname://localhost/TkJoyStick0")
local ec = comps[1]:get_owned_contexts()[1]
ec:set_rate(10)
起動時にアクティブ化するRTCを指定します。
coppeliaSim.exe
と同じフォルダのrtc.confを読み込みます。