RTM-Lua

View the Project on GitHub Nobu19800/RTM-Lua

CoppeliaSim上で動作するRTCの作成方法

このページでは物理シミュレータCoppeliaSim上で動作する上で動作するRTCを作成して、以下のようにPython版サンプルコンポーネントのジョイスティックコンポーネントと接続して車体を操作するシステムの作成を行います。 CoppeliaSim 4.3で動作確認しています。

CoppeliaSimのインストール

以下からCoppeliaSimのインストーラーを入手してインストールしてください。

CoppeliaSimにOpenRTM Lua版をインストール

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以下にコピーします。

imagecopy1

openrtm-lua-x.y.z-cc-x64-lua5.3-versionomit\lua\idlフォルダを(C:\Program Files\CoppeliaRobotics\CoppeliaSimEdu、もしくはCoppeliaSim_Edu_V4_3_0_Ubuntu18_04)にコピーします。

imagecopy2

以下、WindowsとUbuntuでコピーするファイルが違います。Ubuntuで使いたいという人は注意してください。

Windowsの場合

openrtm-lua-x.y.z-cc-x64-lua5.3-versionomit\clibs\以下のファイルを全てC:\Program Files\CoppeliaSim3\CoppeliaSim_PRO_EDU\luar\以下にコピーしてください。

imagecopy3

Ubuntuの場合

以下からluamodule_ubuntu_lua53を入手してください。

中身のファイルを全てCoppeliaSim_Edu_V4_3_0_Ubuntu18_04/以下にコピーしてください。

vrep200

RTC作成

RTC BuilderによるRTCの基本的な作成手順は以下のページを参考にしてください。

上のページの作成手順に従って、以下の仕様のRTCを作成してください。

基本プロファイル

   
モジュール名 CoppeliaSimSample

アクティビティ

onExecuteを有効にしてください。

インポート

   
ポート名 in
データ型 RTC::TimedFloatSeq

CoppeliaSimSample.luaの編集

ソースコードの先頭付近に以下の行を追加して、シミュレーションのスレッドと自動的に切り替える機能をオフにしてください。

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_actuationsysCall_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コンポーネントの起動

TkJoyStickコンポーネントを入手して、TkJoyStickComp.exeを実行してください。

ロボット配置

robots->mobile->Robotnik_Summit_XL140701.ttmをドラックアンドドロップして配置します。 openrtmlua380 new scene(scene1)のツリーからRobotnik_Summit_XLの名前の右にあるアイコンをクリックするとLuaスクリプトの編集ウインドウが起動します。 openrtmlua390 その上に先ほど作成したCoppeliaSimSample.luaのソースコードを全て上書きしてください。 imagesourcecode

RTC起動

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

RTSystem作成

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

system0

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

system1

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

sysrem3

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

system4

ここでTkJoyStick0の実行周期を10Hz定します。デフォルトでは1000Hzですが、CoppeliaSimSample0側のデータ受信の頻度が多いとシミュレーションが遅くなるため調整します。 システムダイアグラム上のTkJoyStick0をクリックして選択後に、Execution Context Viewタブを表示します。 その後、rate10に変更後、適用ボタンを押します。

system5

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

system6

コネクタ接続、RTCのアクティブ化の自動化

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オプションでパラメータの設定ができます。

起動時に接続するポートを指定します。 この場合はCoppeliaSimSample0というRTCのinというデータポートを、TkJoyStick0というRTCのposというポートに接続します。

ただし、TkJoyStick0は別プロセスで起動しているため、rtcname形式による指定が必要になります。 rtcname形式はネームサーバーからRTCを取得する方法です。rtcname://アドレス/RTC名.ポート名で指定します。

また、以下のコードを追加することで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を指定します。

rtc.confのパス

coppeliaSim.exeと同じフォルダのrtc.confを読み込みます。