#################################### ##FILL ME IN #################################### ## links to any required tutorials ## note.0= [[ja/actionlib_tutorials/Tutorials/SimpleActionServer(ExecuteCallbackMethod)|writing a simple action server using the execute 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= ## what level user is this tutorial for ## level= BeginnerCategory #################################### <> <> === コード === まず、`learning_actionlib/src/fibonacci_client.cpp` をエディタで開き、以下を記述してください。: {{{ #!cplusplus block=action #include #include #include #include int main (int argc, char **argv) { ros::init(argc, argv, "test_fibonacci"); // create the action client // true causes the client to spin its own thread actionlib::SimpleActionClient ac("fibonacci", true); ROS_INFO("Waiting for action server to start."); // wait for the action server to start ac.waitForServer(); //will wait for infinite time ROS_INFO("Action server started, sending goal."); // send a goal to the action learning_actionlib::FibonacciGoal goal; goal.order = 20; 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."); //exit return 0; } }}} === コードの説明 === さて、コードを噛み砕いていきましょう。 <> * `actionlib/client/simple_action_client.h` はシンプルアクションクライアントを実装するためのアクションライブラリです。 * `actionlib/client/terminal_state.h` は可能なゴール状態を定義します。 <> これは上記の`Fibonacci.action`ファイルから生成されたアクションメッセージを含みます。 これは[[http://www.ros.org/doc/api/actionlib_tutorials/html/msg/FibonacciAction.html|FibonacciAction.msg]]ファイルから生成されたヘッダファイルです。 メッセージの定義についての詳細は、[[msg]]ページをご覧ください。 <> アクションクライアントはアクションの定義から作られます。 アクションの定義はアクションサーバーとどのようなメッセージ型で通信するかを記述します。 アクションクライアントのコンストラクタは2つの引数を取ります。接続するサーバーの名前とスレッドを自動的に回すための真偽値オプションです。 もしスレッドを使いたくなければ(そして、`actionlib`に暗に`thread magic`をするようにしてほしければ)、これは都合のよいオプションとなるでしょう。 ここではアクションクライアントをサーバー名と自動スピンオプションを真にしたものを用いて生成しています。 <> アクションサーバーが起動し実行されていない可能性があるので、アクションクライアントはアクションサーバーが実行するまで待ちます。 <> ここではゴールメッセージが作られます。ゴールの値が設定されアクションサーバーに送信されます。 <> アクションクライアントはゴールが終えるまで待ちます。 待ち時間のタイムアウトは30秒に設定されています。これはつまり,関数は30秒後以降はgoalが終わっていなければfalseを返すということです。 <> もしタイムアウトより前にゴールが終われば、ゴール状態が返ってきます。 さもなければ、ユーザーにゴールが指定の時間内に得られなかったことを知らせます。 === クライアントのコンパイルと実行 === 以下の行を`CMakeLists.txt`ファイルに追記してください: <> {{{{#!wiki buildsystem catkin {{{ add_executable(fibonacci_client src/fibonacci_client.cpp) target_link_libraries( fibonacci_client ${catkin_LIBRARIES} ) }}} }}}} {{{{#!wiki buildsystem rosbuild {{{ rosbuild_add_executable(fibonacci_client src/fibonacci_client.cpp) rosbuild_link_boost(fibonacci_client thread) }}} }}}} 実行可能にしたら、新しいターミナルでroscoreを起動しましょう。 {{{ $ roscore }}} そして、クライアントを走らせます.: {{{ $ rosrun learning_actionlib fibonacci_client }}} 以下のような結果が見られるでしょう。: . {{{ [ INFO] 1250806286.804217000: Started node [/test_fibonacci], pid [9414], bound on [aqy], xmlrpc port [35466], tcpros port [55866], logging to [~/ros/ros/log/test_fibonacci_9414.log], using [real] time [ INFO] 1250806287.828279000: Waiting for action server to start. }}} クライアントがきちんと動いていることをチェックするために、配信されているROSトピックをリストアップしてみましょう。: {{{ $ rostopic list -v }}} 以下のような結果が得られるでしょう。: . {{{ Published topics: * /fibonacci/goal [learning_actionlib/FibonacciActionGoal] 1 publisher * /fibonacci/cancel [actionlib_msgs/GoalID] 1 publisher * /rosout [rosgraph_msgs/Log] 1 publisher * /rosout_agg [rosgraph_msgs/Log] 1 publisher Subscribed topics: * /fibonacci/feedback [learning_actionlib/FibonacciActionFeedback] 1 subscriber * /rosout [rosgraph_msgs/Log] 1 subscriber * /fibonacci/status [actionlib_msgs/GoalStatusArray] 1 subscriber * /fibonacci/result [learning_actionlib/FibonacciActionResult] 1 subscriber }}} ##Alternatively you can look at the nodes: もしくは、ノードを見ることもできます。: {{{ $ rxgraph }}} ##Or, starting with Groovy: Groovy以降のバージョンであれば以下のようにしてください。: {{{ $ rqt_graph }}} ##{{http://www.ros.org/wiki/actionlib_tutorials/Tutorials/SimpleActionClient?action=AttachFile&do=get&target=fibonacci_client.png||width="100%"}} {{attachment:fibonacci_client_hydro.png||width="100%"}} クライアントがフィードバックと状態、リザルトのチャネルを期待通りに購読していて、またゴールとキャンセルチャネルを期待通り配信しているのがわかります。 クライアントはきちんと起動して実行されています。 === サーバーとクライアントを接続する === 次のactionlibのチュートリアルのために、`Ctrl-C`でアクションクライアントを止め、[[ja/actionlib_tutorials/Tutorials/RunningServerAndClient|run the action server and client]]ページに行きましょう。 ## TutorialCategory ## CommonStackTutorial