2012年1月19日木曜日

rosjavaのサービスを試す

(この記事は2011/01/19現在のものです。rosjavaは開発が盛んなので、ここに書いてあることがすでに古くなっている可能性が高いです。1週間で劇的に変化します。ご注意ください)

これまでにrosjavaのインストール、rosjavaチュートリアル(pub/sub)の実行、
Publisher、Subscriberを見てきました。

今回からrosjavaのサービスを利用してみます。

まずはパッケージの準備です。
rosjavaはビルドシステムを作るのがめんどうなので、rosjava_tutorial_pubsubをコピーします。

roscd rosjava_core
cp -r rosjava_tutorial_pubsub rosjava_tutorial_service
次にmanifest.xmlのrosjava-pathelementを修正します。
また、test_rosパッケージのAddTwoIntsサービスを利用するので、dependに追加しておきます。

<package>
  <description brief="rosjava_tutorial_service">

    rosjava_tutorial_service

  </description>
  <author>OTL</author>
  <license>BSD</license>
  <review status="unreviewed" notes=""/>
  <url>http://ros.org/wiki/rosjava_tutorial_service</url>

  <depend package="rosjava" />
  <depend package="test_ros" />

  <export>
    <rosjava-src location="src/main/java" />
    <rosjava-pathelement location="target/" groupId="org.ros" artifactId="org.ros.rosjava.tutorials.service" version="0.0.0" built="true" />
  </export>
</package>
あとは特に変更の必要はありません。
src/main/java/org/ros/tutorials/pubsubを削除して、
src/main/java/org/ros/tutorials/service/以下にソースを書きましょう。

サービスサーバは以下のような感じ。Server.javaとして保存しましょう。

/* rosjava service server sample*/

package org.ros.tutorials.service;

import org.apache.commons.logging.Log;
import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
import org.ros.node.Node;
import org.ros.node.NodeMain;
import org.ros.node.service.ServiceServer;
import org.ros.internal.node.service.ServiceResponseBuilder;
import org.ros.service.test_ros.AddTwoInts;


public class Server implements NodeMain {

  @Override
  public GraphName getDefaultNodeName() {
    return new GraphName("rosjava_tutorial_service/server");
  }
 
  @Override
  public void onStart(Node node) {
    final Log log = node.getLog();
    ServiceServer<AddTwoInts.Request, AddTwoInts.Response>
        server = node.newServiceServer("/add_two_ints",
                                       "test_ros/AddTwoInts",
      new ServiceResponseBuilder<AddTwoInts.Request, AddTwoInts.Response>() {
        @Override
        public AddTwoInts.Response build(AddTwoInts.Request request) {
          AddTwoInts.Response res = new AddTwoInts.Response();
          res.sum = request.a + request.b;
          log.info("add " + request.a + ", " + request.b);
          return res;
        }
                                       });

  }

  @Override
  public void onShutdown(Node node) {
  }

  @Override
  public void onShutdownComplete(Node node) {
  }
}

ServiceServerの型にRequestとResponseの両方を入れないといけないところがC++と違いますね。
また、ServiceResponseBuilderというものを使ってコールバックを書くようです。
(なぜか現在org.ros.internal.node.service.ServiceResponseBuilderという、internalなところにあるクラスです)


次は呼び出す方、Client.javaです。

/* rosjava service client sample
 */

package org.ros.tutorials.service;

import com.google.common.base.Preconditions;

import org.apache.commons.logging.Log;
import org.ros.node.Node;
import org.ros.node.NodeMain;
import org.ros.namespace.GraphName;
import org.ros.node.service.ServiceClient;
import org.ros.node.service.ServiceResponseListener;
import org.ros.exception.RemoteException;
import org.ros.service.test_ros.AddTwoInts;

/*
 * @author OTL
 */
public class Client implements NodeMain {
  @Override
  public GraphName getDefaultNodeName() {
    return new GraphName("rosjava_tutorial_service/client");
  }

  @Override
  public void onStart(Node node) {
    final Log log = node.getLog();
    try {
      ServiceClient<AddTwoInts.Request, AddTwoInts.Response> client =
          node.newServiceClient("/add_two_ints", "test_ros/AddTwoInts");
      Thread.sleep(100);
      AddTwoInts.Request srv = new AddTwoInts.Request();
      srv.a = 5;
      srv.b = 1;
      client.call(srv, new ServiceResponseListener<AddTwoInts.Response>() {
            @Override
                public void onSuccess(AddTwoInts.Response res) {
              log.info("call service success! " + res.sum);
            }
            @Override
                public void onFailure(RemoteException arg) {
              log.info("call service fail");
            }
        });
    } catch (Exception e) {
      if (node != null) {
        node.getLog().fatal(e);
      } else {
        e.printStackTrace();
      }
    }
  }

  @Override
  public void onShutdown(Node node) {
  }

  @Override
  public void onShutdownComplete(Node node) {
  }
}

こちらもRequestとResponseの両方の型をいれますね。
そして、callの成否時の処理をServiceResponseListenerに書くようです。

あとは普通にmakeすればできあがりです。
実行するにはroscoreを上げて、
サーバは

rosrun rosjava_bootstrap run.py rosjava_tutorial_service org.ros.tutorials.service.Server

クライアントは
rosrun rosjava_bootstrap run.py rosjava_tutorial_service org.ros.tutorials.service.Client

のように実行します。
ちなみにサーバをテストしようとして、
rosservice call /add_two_ints 1 2
とするとエラーになります。どうやらrosservice args /add_two_intsがうまく動いていないようです。

rosserviceが使えないので、サーバだけ動作確認したい場合は
rosrun test_ros add_two_ints_client
とするといいと思います。

0 件のコメント:

コメントを投稿