Note: This tutorial assumes that you have completed the previous tutorials: writing a threaded simple action client.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

アクションサーバとクライアントを他のノードとともに実行する

Description: このチュートリアルは、平均化するアクションサーバとクライアントを他のデータノードと共に実行し、チャネルの出力とノードグラフを可視化について扱います。

Tutorial Level: INTERMEDIATE

データノードを書く

actionサーバとクライアントを動かす前に、データノードを作っておく必要があります。エディタでlearning_actionlib/scripts/gen_numbers.pyを作り、以下の内容をファイルに書きこんでください:

   1 #!/usr/bin/env python
   2 import roslib; roslib.load_manifest('learning_actionlib')
   3 import rospy
   4 from std_msgs.msg import Float32
   5 import random
   6 def gen_number():
   7     pub = rospy.Publisher('random_number', Float32)
   8     rospy.init_node('random_number_generator', log_level=rospy.INFO)
   9     rospy.loginfo("Generating random numbers")
  10 
  11     while not rospy.is_shutdown():
  12         pub.publish(Float32(random.normalvariate(5, 1)))
  13         rospy.sleep(0.05)
  14 
  15 if __name__ == '__main__':
  16   try:
  17     gen_number()
  18   except Exception, e:
  19     print "done"

上記のコードは正規分布で中央値5、標準偏差1の乱数を生成します。random_numberトピックでこの乱数を配信します。

ノードのアクセス権限を実行可能にするのを忘れないように:

  • chmod +x gen_numbers.py

データノードを起動する

新しいターミナルでのroscore起動から始めます:

$ roscore

そして別の新しいターミナルでデータノードを開始します:

rosrun learning_actionlib gen_numbers.py 

以下のような出力が見えるでしょう:

  • [INFO] [WallTime: 1412736999.048881] Generating random numbers

アクションのフィードバックを見る

新しいターミナルで、actionサーバからのフィードバックを見るためにフィードバックチャネルをrostopicします:

$ rostopic echo /averaging/feedback

ゴールに達するまでサーバが動作している間、以下のような出力が見えるでしょう:

  • ---
    header: 
      seq: 1
      stamp: 1251489509536852000
      frame_id: 
    status: 
      goal_id: 
        stamp: 1251489509511553000
        id: 1251489509.511553000
      status: 1
      text: 
    feedback: 
      sample: 1
      data: 3.96250081062
      mean: 3.96250081062
      std_dev: 0.000687940046191
    ---
    header: 
      seq: 2
      stamp: 1251489509588828000
      frame_id: 
    status: 
      goal_id: 
        stamp: 1251489509511553000
        id: 1251489509.511553000
      status: 1
      text: 
    feedback: 
      sample: 2
      data: 5.16988706589
      mean: 4.56619405746
      std_dev: 0.60369348526
    ---

アクションの結果を見る

新しいターミナルで、actionサーバからのフィードバックを見るためにフィードバックチャネルをrostopicします:

$ rostopic echo /averaging/result

ゴールが完了した後に、以下のような出力を見るでしょう:

  • ---
    header: 
      seq: 1
      stamp: 1251489786993936000
      frame_id: 
    status: 
      goal_id: 
        stamp: 1251489781746524000
        id: 1251489781.746524000
      status: 4
      text: 
    result: 
      mean: 4.99936008453
      std_dev: 1.10789334774

アクションのノードグラフを見る

rostopicの代わりに、ノードを見ることもできます:

  Show EOL distros: 

$ rxgraph &

$ rxgraph &

$ rosrun rqt_graph rqt_graph &

averaging_client_server_hydro.png

クライアントとサーバを起動する

新しいターミナルでactionサーバを開始します:

$ rosrun learning_actionlib averaging_server

アクションが処理を完了した時、サンプリングされたランダムデータに依って、成功か失敗のINFOメッセージを出力するでしょう。

[ INFO] [1412745704.439411272]: /averaging: Succeeded

そして、新しいターミナルでactionクライアントを起動します:

$ rosrun learning_actionlib averaging_client

クライアントがゴールの到達の通知を受け取ると、actionの結果と共にINFOメッセージを出力するでしょう。

  • [ INFO] [1412745704.439866194]: Action finished: SUCCEEDED

Wiki: ja/actionlib_tutorials/Tutorials/RunningServerAndClientWithNodes (last edited 2014-10-08 05:27:42 by Moirai)