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に追加しておきます。

  1. <package>  
  2.   <description brief="rosjava_tutorial_service">  
  3.   
  4.     rosjava_tutorial_service  
  5.   
  6.   </description>  
  7.   <author>OTL</author>  
  8.   <license>BSD</license>  
  9.   <review status="unreviewed" notes=""/>  
  10.   <url>http://ros.org/wiki/rosjava_tutorial_service</url>  
  11.   
  12.   <depend package="rosjava" />  
  13.   <depend package="test_ros" />  
  14.   
  15.   <export>  
  16.     <rosjava-src location="src/main/java" />  
  17.     <rosjava-pathelement location="target/" groupId="org.ros" artifactId="org.ros.rosjava.tutorials.service" version="0.0.0" built="true" />  
  18.   </export>  
  19. </package>  
あとは特に変更の必要はありません。
src/main/java/org/ros/tutorials/pubsubを削除して、
src/main/java/org/ros/tutorials/service/以下にソースを書きましょう。

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

  1. /* rosjava service server sample*/  
  2.   
  3. package org.ros.tutorials.service;  
  4.   
  5. import org.apache.commons.logging.Log;  
  6. import org.ros.message.MessageListener;  
  7. import org.ros.namespace.GraphName;  
  8. import org.ros.node.Node;  
  9. import org.ros.node.NodeMain;  
  10. import org.ros.node.service.ServiceServer;  
  11. import org.ros.internal.node.service.ServiceResponseBuilder;  
  12. import org.ros.service.test_ros.AddTwoInts;  
  13.   
  14.   
  15. public class Server implements NodeMain {  
  16.   
  17.   @Override  
  18.   public GraphName getDefaultNodeName() {  
  19.     return new GraphName("rosjava_tutorial_service/server");  
  20.   }  
  21.    
  22.   @Override  
  23.   public void onStart(Node node) {  
  24.     final Log log = node.getLog();  
  25.     ServiceServer<AddTwoInts.Request, AddTwoInts.Response>  
  26.         server = node.newServiceServer("/add_two_ints",  
  27.                                        "test_ros/AddTwoInts",  
  28.       new ServiceResponseBuilder<AddTwoInts.Request, AddTwoInts.Response>() {  
  29.         @Override  
  30.         public AddTwoInts.Response build(AddTwoInts.Request request) {  
  31.           AddTwoInts.Response res = new AddTwoInts.Response();  
  32.           res.sum = request.a + request.b;  
  33.           log.info("add " + request.a + ", " + request.b);  
  34.           return res;  
  35.         }  
  36.                                        });  
  37.   
  38.   }  
  39.   
  40.   @Override  
  41.   public void onShutdown(Node node) {  
  42.   }  
  43.   
  44.   @Override  
  45.   public void onShutdownComplete(Node node) {  
  46.   }  
  47. }  

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


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

  1. /* rosjava service client sample 
  2.  */  
  3.   
  4. package org.ros.tutorials.service;  
  5.   
  6. import com.google.common.base.Preconditions;  
  7.   
  8. import org.apache.commons.logging.Log;  
  9. import org.ros.node.Node;  
  10. import org.ros.node.NodeMain;  
  11. import org.ros.namespace.GraphName;  
  12. import org.ros.node.service.ServiceClient;  
  13. import org.ros.node.service.ServiceResponseListener;  
  14. import org.ros.exception.RemoteException;  
  15. import org.ros.service.test_ros.AddTwoInts;  
  16.   
  17. /* 
  18.  * @author OTL 
  19.  */  
  20. public class Client implements NodeMain {  
  21.   @Override  
  22.   public GraphName getDefaultNodeName() {  
  23.     return new GraphName("rosjava_tutorial_service/client");  
  24.   }  
  25.   
  26.   @Override  
  27.   public void onStart(Node node) {  
  28.     final Log log = node.getLog();  
  29.     try {  
  30.       ServiceClient<AddTwoInts.Request, AddTwoInts.Response> client =  
  31.           node.newServiceClient("/add_two_ints""test_ros/AddTwoInts");  
  32.       Thread.sleep(100);  
  33.       AddTwoInts.Request srv = new AddTwoInts.Request();  
  34.       srv.a = 5;  
  35.       srv.b = 1;  
  36.       client.call(srv, new ServiceResponseListener<AddTwoInts.Response>() {  
  37.             @Override  
  38.                 public void onSuccess(AddTwoInts.Response res) {  
  39.               log.info("call service success! " + res.sum);  
  40.             }  
  41.             @Override  
  42.                 public void onFailure(RemoteException arg) {  
  43.               log.info("call service fail");  
  44.             }  
  45.         });  
  46.     } catch (Exception e) {  
  47.       if (node != null) {  
  48.         node.getLog().fatal(e);  
  49.       } else {  
  50.         e.printStackTrace();  
  51.       }  
  52.     }  
  53.   }  
  54.   
  55.   @Override  
  56.   public void onShutdown(Node node) {  
  57.   }  
  58.   
  59.   @Override  
  60.   public void onShutdownComplete(Node node) {  
  61.   }  
  62. }  

こちらも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 件のコメント:

コメントを投稿