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

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

V-REPとROSの連携

ROSからV-REPを動かすときにやったことをメモ.自作のロボットモデルを想定.Luaは使わない.環境はubuntu14.04のROS indigo.

ROSで動くc++のプログラムからシミュレーションの開始と終了,時刻の同期,関節の操作などを確認.

 

※ V-REP Ver3.4から方法が変わりました(本記事における1, 2の部分).Ver3.4用のものは以下を参考にしてください(2017/6/14追記)

tattatatakemori.hatenablog.com

 

はじめに

卒業研究のシミュレーションで始めてV-REPを使いましたが,その時はまだROSを使っていませんでした.その後実機をROSで開発したので,シミュレータもそのROSのシステムに組み込みたくなりました.ROSと連携させるシミュレータとしてはGazeboも有名ですが,僕はV-REPを使います.

V-REPにはもともとROS連携機能がついており,V-REP上でROSノードが走りPubしたりSubしたりできるようです.この機能についてはほとんど知らないのですが,ドキュメントがあまりなさそうなこと,V-REP上でLuaでいくらか書く必要がありそうなこと,シーンファイルを作り直したらそのソースをコピペしないといけなさそうなことなど,なんとなく嫌です.

そこで,シーンファイル上でどうこうするのではなく,ROS上でremoteAPIを走らせて使うことにして,導入部分ができたっぽいのでメモしておきます.

※僕はプログラミングにもV-REPにもあまり詳しくありません

やったこと

1 ROSとV-REPを連携させる

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

以下のパッケージをROSのワークスペースに追加

  • vrep_plugin
  • vrep_common
  • vrep_joy
  • ros_bubble_rob

これでcatkin_makeする.

また,compiledRosPluginsフォルダの中身をV-REPのフォルダ直下に置く.

1.2 roscoreの後にV-REPを起動する

roscoreしたあと,V-REPがあるディレクトリで移動して

./vrep.sh

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

rqt_graghなどで確認する.

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

$ rostopic list 
/rosout
/rosout_agg
/tf
/vrep/info

2 時刻を同期させる

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

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

2.1 シミュレータ時刻を使うようROSを設定

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

rosparam set use_sim_time true

VREPを立ち上げた後にしても前にしても特に問題はなかった.

2.2 シミュレーション時刻をROSで受け取る

2.1だけでは不足.シミュレータの時刻をROSに伝える必要がある.以下のフォーラムで質問されていて,ここの解答の通りにしたらうまくいった.

http://www.forum.coppeliarobotics.com/viewtopic.php?t=179

rosrun topic_tools transform /vrep/info /clock rosgraph_msgs/Clock 'rospy.Time.from_sec(m.simulationTime.data)' --import rospy
2.3 launchファイルで設定

2.1と2.2はlaunchファイルでまとめてあれすることができる.

<param name="use_sim_time" value="true" />
<node name="sim_time" pkg="topic_tools" type="transform" args="/vrep/info /clock rosgraph_msgs/Clock 'rospy.Time.from_sec(m.simulationTime.data)' --import rospy" />

3 remoteAPIをROSで使う(C++)

だいたいここに書いてある.

Enabling the Remote API - client side

3.1 APIを取ってくる

V-REPのインストールフォルダの中から以下のファイルを取ってくる.これらをパッケージのsrcフォルダにコピー.

  • extApi.c/h

  • extApiPlatform.c/h

  • extApiInternal.h

  • v_repConst.h

3.2 CMakeLists.txtを編集

CmakeList.txtのadd_executableにextAPI.cとextApiPlatform.cを追加.たぶんこの順番であるべき.

3.3 プリプロセッサ指令を追加

Enabling the Remote API - client sideには次の記述がある.

Make sure you have defined NON_MATLAB_PARSING and MAX_EXT_API_CONNECTIONS=255 as a preprocessor definition.

たしかに /V-REP/programming/remoteApiBindings/libにあるmakefileにはそう書かれている.

CFLAGS = -I../../include -I../../remoteApi -Wall -DNON_MATLAB_PARSING -DMAX_EXT_API_CONNECTIONS=255 -fPIC

ROSの場合CMakefile.txtに該当するものを書けばいいのか,そのあたりがよく分からなかったので,expApi.hとextApiPlatform.hの先頭に以下のコードを追加して対応.

#define NON_MATLAB_PARSING
#define MAX_EXT_API_CONNECTIONS 255

これでcatkin_makeが通った.

自分のソースにincludeするのはexpApi.hだけでよい.

extern "C" {
  #include "extApi.h"
}

3' Pythonの場合

3.1のところで持ってくるのが次のものになるだけのはず.

  • vrep.py
  • vrepConst.py
  • remoteApi.so

remoteApi.soは32bitと64bitのがあるので注意.pythonの場合は3.2と3.3はいらない.

4 remoteAPIを使って書く

Remote API function list (by category)

ここにあるAPIを使えばC/C++PythonからV-REPを操作できる.記事の最後に僕のコードを一部載せておきます.

まとめ

この記事ではROSとV-REPを連携させるためにやったことを書きました.

そもそも,V-REPがわざわざ公式にROSとがっつり連携できるようにサポートしてるわけですから,本来はそのやり方に則るのがいいと思います.

今回のやり方がうれしいのは僕のような以下の場合.

  • V-REP上でごちゃごちゃしたくないし,なんだかLuaを書きたくない
  • 自作のロボットモデルを使用(ROS連携対応済みのサンプルとかを使わない)
  • 自作のメッセージ型を多用(どのみちV-REPから直接Pubできない?ので)
  • 以前remoteAPIを使ったことがありそれに慣れている

このような場合にはもしかしたらこちらのやり方の方がてっとり早いかもしれません.また,ROSに依存する部分が少ないのでコードを使い回しやすいかもしれません.

サンプルコード

僕の書いたコードの一部です.色々保証はしません. 

#include <ros/ros.h>
extern "C" {
  #include "extApi.h"
}

class Vrep {
 public:
  static bool ConnectToVrep();
  static void StartSimulation();

 private:
  static simxInt client_id_;  // V-REP接続ID
};

/** @fn
 * @brief V-REPに接続する
 * @param なし
 * @return (bool) false:接続失敗
 */
bool Vrep::ConnectToVrep() {
  simxFinish(-1);  // 念のため,先に全ての操作を終了
  ROS_INFO("Connecting to v-rep");
  client_id_ = simxStart(/* connectionAddress = */ (simxChar*)"127.0.0.1",
                         /* connectionPort = */ 19997,  // 19997にすればvrep側を手動で開始する必要がない
                         /* waitUntilConnected = */ true,
                         /* doNotReconnectOnceDisconnected = */ true,
                         /* timeOutInMs = */ 5000,
                         /* commThreadCycleInMs = */ 5);
  if (client_id_ == -1) {
    ROS_ERROR("Could not connect to V-REP remote API server");
    return false;
  } else {
    ROS_INFO("Connected to V-REP remote API server");
    return true;
  }
}

/** @fn
 * @brief シミュレーションを開始する
 * @param なし
 * @return なし
 */
void Vrep::StartSimulation() {
  simxStartSimulation(client_id_, simx_opmode_oneshot_wait);
  ROS_INFO("Simulation is started.");
}

simxInt Vrep::client_id_;