#################################### ##FILL ME IN #################################### ## links to any required tutorials ## note.0= [[actionlib_tutorials/Tutorials/SimpleActionServer(GoalCallbackMethod)|writing a simple action server using the goal callback method]] ## descriptive title for the tutorial ## title = スレッドのシンプルなアクションクライアントを書く ## multi-line description to be displayed in search ## description = このチュートリアルは、`simple_action_client`ライブラリを使って、平均化するアクションクライアントの作成を扱います。このサンプルプログラムはスレッドを回し、アクションクライアントを作成し、ゴールをアクションサーバーに送ります。 ## the next tutorial description ## next = ## links to next tutorial ## next.0.link= [[ja/actionlib_tutorials/Tutorials/RunningServerAndClientWithNodes|アクションサーバとクライアントを他のノードとともに実行する]] ## what level user is this tutorial for ## level= IntermediateCategory #################################### <> <> <> ##=== The Code === === コード === ##First, create learning_actionlib/src/averaging_client.cpp in your favorite editor, and place the following inside it: まず、learning_actionlib/src/averaging_client.cppをエディタで開き、以下をファイルに書き込みます: {{{ #!cplusplus block=action #include #include #include #include #include void spinThread() { ros::spin(); } int main (int argc, char **argv) { ros::init(argc, argv, "test_averaging"); // create the action client actionlib::SimpleActionClient ac("averaging"); boost::thread spin_thread(&spinThread); ROS_INFO("Waiting for action server to start."); ac.waitForServer(); ROS_INFO("Action server started, sending goal."); // send a goal to the action learning_actionlib::AveragingGoal goal; goal.samples = 100; ac.sendGoal(goal); //wait for the action to return bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0)); if (finished_before_timeout) { actionlib::SimpleClientGoalState state = ac.getState(); ROS_INFO("Action finished: %s",state.toString().c_str()); } else ROS_INFO("Action did not finish before the time out."); // shutdown the node and join the thread back before exiting ros::shutdown(); spin_thread.join(); //exit return 0; } }}} ##=== The Code Explained === === コード解説 === ##Now, let's break down the code piece by piece. では、一つずつコードを分析していきましょう。 <> * actionlib/server/simple_action_client.h はシンプルなactionを実装する際に使うactionライブラリです。 * actionlib/client/terminal_state.h は考えられるゴールの状態を定義しています。 ## * actionlib/server/simple_action_client.h is the action library used from implementing simple action clients. ## * actionlib/client/terminal_state.h defines the possible goal states. <> ##This includes action message generated from the Averaging.action file show above. This is a header generated automatically from the [[http://www.ros.org/doc/api/actionlib_tutorials/html/msg/AveragingAction.html|AveragingAction.msg]] file. For more information on message definitions, see the [[msg]] page. ここは、前述のAveraging.actionファイルで生成したactionメッセージをインクルードしています。これは、[[http://www.ros.org/doc/api/actionlib_tutorials/html/msg/AveragingAction.html|AveragingAction.msg]]ファイルから自動的に発生するヘッダです。 メッセージ定義の詳細については、[[msg]]ページを参照してください。 <> ##This includes the boost thread library for spinning the thread in this example. ここはboostのスレッドライブラリをインクルードしています。この例の中でスレッドを回します。 <> ##Here is a simple function for spinning a thread that will be used later in the code. This thread will spin the ros node in the background. ここは、コードの中で後に使われる、スレッドを回すための単純な関数です。このスレッドはバックグラウンドでROSノードをスピンします。 <> ##The action client is template on the action definition, specifying what message types to communicate to the action server with. The action client constructor also takes two arguments, the server name to connect to and a boolean option to automatically spin a thread. Here the action client is constructed with the server name and the auto spin option set to false, which means a thread must be created. actionクライアントはactionの定義上のテンプレートで、actionサーバとどんなメッセージタイプで通信するかについて指定します。actionクライアントのコンストラクタは2つの引数、接続するサーバ名と自動的にスレッドを回すためのオプションのbooleanを取ります。ここではactionクライアントは、サーバ名と自動のスピンオプションを、スレッドが生成されることを意味するfalseにセットして構築します。 <> ##Here the thread is created and the ros node is started spinning in the background. By using this method you can create multiple threads for your action client if needed. ここでスレッドが作られ、バックグラウンドでROSノードのスピンが開始されます。この方法を使って、必要であればactionクライアントのマルチスレッドを作ることができます。 <> ##Since the action server may not be up and running, the action client will wait for the action server to start before continuing. actionサーバが未起動で動いていない場合があるので、actionクライアントは処理を続ける前に、actionサーバが動き出すのを待ちます。 <> ##Here a goal msg is created, the goal value is set and sent to the action server. ここではゴールメッセージを生成し、ゴールの値をセットしてactionサーバに送ります。 <> ##The action client now waits for the goal to finish before continuing. The timeout on the wait is set to 30 seconds, this means after 30 seconds the function will return with false if the goal has not finished. actionクライアントは、処理を続ける前にゴールが完了するのをここで待ちます。待機のタイムアウトは30秒に設定されていて、もしゴールが終わっていない場合は30秒後に関数がfalseで返ってくることを、ここは意味しています。 <> ##If the goal finished before the time out the goal status is reported, else the user is notified that the goal did not finish in the allotted time. ゴールがタイムアウトの前に終わった場合はゴールステータスが報告され、終らなかった場合は、割り当てられた時間にゴールが終わらなかったことがユーザに通知されます。 <> ##Now that the goal is completed and we have reported the goal status, we need to shutdown the ros node and join our thread back before exiting. そして、ゴールが完了しゴールの状態が通知され、ROSノードをシャットダウンし、関数からexitする前にスレッドをjoinに戻します。 ##=== Compiling and Running the Client === === クライアントをコンパイルし実行する === ##Add the following line to your CMakeLists.txt file: 以下の行を、CMakeLists.txtファイルに追加します: {{{{{#!wiki buildsystem rosbuild {{{ rosbuild_add_executable(averaging_client src/averaging_client.cpp) }}} }}}}} {{{{{#!wiki buildsystem catkin {{{ add_executable(averaging_client src/averaging_client.cpp) target_link_libraries(averaging_client ${catkin_LIBRARIES}) }}} }}}}} ##After you have made the executable by `catkin_make`, start a roscore in a new terminal: `catkin_make`で実行ファイルを生成した後、新しいターミナルでroscoreをスタートさせます: {{{ $ roscore }}} ##And then run the client: そして、クライアントを実行します: {{{ $ rosrun learning_actionlib averaging_client }}} ##You will see something similar to: 以下のような出力が見えるでしょう: . {{{ [ 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. }}} ##To check that your client is running properly, list topics being published: クライアントが正しく動作しているかをチェックするために、配信されているtopicをリストします: {{{ $ rostopic list -v }}} ##You will see something similar to: 以下のような出力が見えるでしょう: . {{{ 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 }}} ##Alternatively you can look at the nodes: rostopicのかわりに、ノードを見ることもできます: <> {{{{{#!wiki version electric {{{ $ rxgraph & }}} }}}}} {{{{{#!wiki version fuerte {{{ $ rxgraph & }}} }}}}} {{{{{#!wiki version groovy hydro {{{ $ rosrun rqt_graph rqt_graph & }}} }}}}} ##{{attachment:averaging_action_client.png||width="100%"}} {{attachment:averaging_action_client_hydro.png||width="100%"}} ##This shows that your client is subscribing to the feedback, status, and result channels as expected and publishing to the goal and cancel channels as expected. The client is up and running properly. これはクライアントがフィードバック、ステータス、結果のチャネルを期待通りに購読していて、ゴールとcancelチャネルを期待通りに配信していることを示しています。クライアントは起動し、正しく動作しています。 ##=== Connecting the Server and Client === === サーバとクライアントを接続する === ##For the next step in using your action, you need to Ctrl-C the action client and [[actionlib_tutorials/Tutorials/RunningServerAndClientWithNodes|run an action server and client with other nodes]]. actionを使った次のステップのために、Ctrl-Cでactionクライアントを停止しておく必要があります。次は[[ja/actionlib_tutorials/Tutorials/RunningServerAndClientWithNodes|run an action server and client with other nodes]]です。 ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE