メカトロニクスにうってつけの日

ロボット開発や研究活動に関するメモ

V-REPとROSの連携(V-REP Ver3.4.0版)

V-REPが3.4にバージョンアップして,ROSとの連携の勝手が変わった.連携のためにしたことをメモしておく.環境はubuntu14.04のROS indigo.従来の方法,および私流のremoteAPIの使い方は以下の記事を参照.

tattatatakemori.hatenablog.com

 

ここで紹介するやり方は概ね公式のチュートリアルに従っている.

http://www.coppeliarobotics.com/helpFiles/en/rosTutorialIndigo.htm

 

1 V-REPの最新版をダウンロード

下記サイトから,適切なV-REPをダウンロードし,展開して適当な場所に置く.私の場合はV-REP PRO EDU V3.4.0 rev1のLinux64bit版.

Coppelia Robotics V-REP: Create. Compose. Simulate. Any Robot: Downloads

以下では,V-REPのrootフォルダは ~/V-REP としている.

2 V-REP用ROSパッケージのビルド

2.1  RosInterfaceのプラグイン?を配置

V-REP/compiledRosPlugins/ にある

  • libv_repExtRosInterface.so
  • libv_repExtRosSkeleton.so

を V-REP/ にコピー.

2.2 パッケージを取ってくる

V-REP/programming/ros_packages/ から以下のパッケージをROSのsrcフォルダにコピー.

  • ros_bubble_rob2
  • v_repExtRosInterface
  • vrep_skeleton_msg_and_srv
  • vrep_plugin_skeleton

2.3 V-REPのrootフォルダへのパスを設定

V-REPのrootフォルダへのパスを通す.

export VREP_ROOT=~/V-REP

bashrcに書いておくとよい?

2.4 ビルド

catkin build コマンドでビルドする.catkin_make では不可.

2.5 連携の確認

roscore したあと,別ターミナルで~/V-REPに移動して

./vrep.sh

でV-REPが起動する.このときにV-REPのノードとかが立ち上がる.

rostopic list で確認すると以下の結果に.

$ rostopic list 
/rosout
/vrep_ros_interface

3 時刻の同期

V-REP上の時刻をROS上の時刻にする.

ros::Rateやros::Timeのいろいろをシミュレーション時刻にするにはこれが必要.

3.1 sceneファイルから時刻情報をPub

sceneファイルから適当なオブジェクトを選んで,[Menu bar --> Add --> Associated child script --> non threaded] によってスクリプトを追加.このスクリプトの編集画面を開き,中身を以下の内容に置き換える.

if (sim_call_type==sim_childscriptcall_initialization) then
    -- The child script initialization
    -- Check if the required RosInterface is there:
    moduleName=0
    index=0
    rosInterfacePresent=false
    while moduleName do
        moduleName=simGetModuleName(index)
        if (moduleName=='RosInterface') then
            rosInterfacePresent=true
        end
        index = index+1
    end

    if rosInterfacePresent then
        -- add publisher /clock
        clockPub=simExtRosInterface_advertise('/clock','rosgraph_msgs/Clock')
    end
end

if (sim_call_type==sim_childscriptcall_actuation) then
    -- Send an updated simulation time message, and send the transform of the object attached to this script:
    if rosInterfacePresent then
        simExtRosInterface_publish(clockPub,{clock=simGetSimulationTime()})
    end
end

if (sim_call_type==sim_childscriptcall_cleanup) then
    -- Following not really needed in a simulation script (i.e. automatically shut down at simulation end):
    if rosInterfacePresent then
        simExtRosInterface_shutdownPublisher(clockPub)
    end
end

ここでは'rosgraph_msgs/Clock'型の'/clock'というトピックにシミュレーション時間を詰めてPubしている.次の設定により,ROSのシステムがこれを受け取ってくれる.

3.2 シミュレータ時刻を使うように設定

以下のコマンドでそのように設定.

rosparam set use_sim_time true

V-REPを立ち上げた後にしても前にしても特に問題はなかった.以下の様にlaunchファイルに書いておくと楽.

<param name="use_sim_time" value="true" />

 

以上.

シミュレーション時間の刻みがros::Timeの分解能になるのが荒くて嫌なので改善できるなら改善したい.