Note: This tutorial assumes that you have completed the previous tutorials: writing a simple action server using the goal callback method. |
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: このチュートリアルは、simple_action_clientライブラリを使って、平均化するアクションクライアントの作成を扱います。このサンプルプログラムはスレッドを回し、アクションクライアントを作成し、ゴールをアクションサーバーに送ります。Tutorial Level: INTERMEDIATE
Next Tutorial: アクションサーバとクライアントを他のノードとともに実行する
Contents
コード
まず、learning_actionlib/src/averaging_client.cppをエディタで開き、以下をファイルに書き込みます:
1 #include <ros/ros.h>
2 #include <actionlib/client/simple_action_client.h>
3 #include <actionlib/client/terminal_state.h>
4 #include <learning_actionlib/AveragingAction.h>
5 #include <boost/thread.hpp>
6
7 void spinThread()
8 {
9 ros::spin();
10 }
11
12 int main (int argc, char **argv)
13 {
14 ros::init(argc, argv, "test_averaging");
15
16 // create the action client
17 actionlib::SimpleActionClient<learning_actionlib::AveragingAction> ac("averaging");
18 boost::thread spin_thread(&spinThread);
19
20 ROS_INFO("Waiting for action server to start.");
21 ac.waitForServer();
22
23 ROS_INFO("Action server started, sending goal.");
24 // send a goal to the action
25 learning_actionlib::AveragingGoal goal;
26 goal.samples = 100;
27 ac.sendGoal(goal);
28
29 //wait for the action to return
30 bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
31
32 if (finished_before_timeout)
33 {
34 actionlib::SimpleClientGoalState state = ac.getState();
35 ROS_INFO("Action finished: %s",state.toString().c_str());
36 }
37 else
38 ROS_INFO("Action did not finish before the time out.");
39
40 // shutdown the node and join the thread back before exiting
41 ros::shutdown();
42 spin_thread.join();
43
44 //exit
45 return 0;
46 }
コード解説
では、一つずつコードを分析していきましょう。
- actionlib/server/simple_action_client.h はシンプルなactionを実装する際に使うactionライブラリです。
- actionlib/client/terminal_state.h は考えられるゴールの状態を定義しています。
ここは、前述のAveraging.actionファイルで生成したactionメッセージをインクルードしています。これは、AveragingAction.msgファイルから自動的に発生するヘッダです。 メッセージ定義の詳細については、msgページを参照してください。
ここはboostのスレッドライブラリをインクルードしています。この例の中でスレッドを回します。
ここは、コードの中で後に使われる、スレッドを回すための単純な関数です。このスレッドはバックグラウンドでROSノードをスピンします。
actionクライアントはactionの定義上のテンプレートで、actionサーバとどんなメッセージタイプで通信するかについて指定します。actionクライアントのコンストラクタは2つの引数、接続するサーバ名と自動的にスレッドを回すためのオプションのbooleanを取ります。ここではactionクライアントは、サーバ名と自動のスピンオプションを、スレッドが生成されることを意味するfalseにセットして構築します。
18 boost::thread spin_thread(&spinThread);
ここでスレッドが作られ、バックグラウンドでROSノードのスピンが開始されます。この方法を使って、必要であればactionクライアントのマルチスレッドを作ることができます。
actionサーバが未起動で動いていない場合があるので、actionクライアントは処理を続ける前に、actionサーバが動き出すのを待ちます。
ここではゴールメッセージを生成し、ゴールの値をセットしてactionサーバに送ります。
actionクライアントは、処理を続ける前にゴールが完了するのをここで待ちます。待機のタイムアウトは30秒に設定されていて、もしゴールが終わっていない場合は30秒後に関数がfalseで返ってくることを、ここは意味しています。
ゴールがタイムアウトの前に終わった場合はゴールステータスが報告され、終らなかった場合は、割り当てられた時間にゴールが終わらなかったことがユーザに通知されます。
そして、ゴールが完了しゴールの状態が通知され、ROSノードをシャットダウンし、関数からexitする前にスレッドをjoinに戻します。
クライアントをコンパイルし実行する
以下の行を、CMakeLists.txtファイルに追加します:
rosbuild_add_executable(averaging_client src/averaging_client.cpp)
add_executable(averaging_client src/averaging_client.cpp) target_link_libraries(averaging_client ${catkin_LIBRARIES})
catkin_makeで実行ファイルを生成した後、新しいターミナルでroscoreをスタートさせます:
$ roscore
そして、クライアントを実行します:
$ rosrun learning_actionlib averaging_client
以下のような出力が見えるでしょう:
[ INFO] 1250806286.804217000: Started node [/test_averaging], pid [9414], bound on [aqy], xmlrpc port [35466], tcpros port [55866], logging to [~/ros/ros/log/test_averaging_9414.log], using [real] time [ INFO] 1250806287.828279000: Waiting for action server to start.
クライアントが正しく動作しているかをチェックするために、配信されているtopicをリストします:
$ rostopic list -v
以下のような出力が見えるでしょう:
Published topics: * /rosout [rosgraph_msgs/Log] 1 publisher * /rosout_agg [rosgraph_msgs/Log] 1 publisher * /averaging/goal [learning_actionlib/AveragingActionGoal] 1 publisher * /averaging/cancel [actionlib_msgs/GoalID] 1 publisher Subscribed topics: * /averaging/status [actionlib_msgs/GoalStatusArray] 1 subscriber * /averaging/result [learning_actionlib/AveragingActionResult] 1 subscriber * /rosout [rosgraph_msgs/Log] 1 subscriber * /averaging/feedback [learning_actionlib/AveragingActionFeedback] 1 subscriber
rostopicのかわりに、ノードを見ることもできます:
Show EOL distros:
$ rxgraph &
$ rxgraph &
$ rosrun rqt_graph rqt_graph &
これはクライアントがフィードバック、ステータス、結果のチャネルを期待通りに購読していて、ゴールとcancelチャネルを期待通りに配信していることを示しています。クライアントは起動し、正しく動作しています。
サーバとクライアントを接続する
actionを使った次のステップのために、Ctrl-Cでactionクライアントを停止しておく必要があります。次はrun an action server and client with other nodesです。