Note: This tutorial assumes that you have completed the previous tutorials: 使用execute callback方法编写一个简单的行为服务器. |
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库来创建一个Fibonacci行为客户端。这个示例程序创建一个行为客户端并且发送一个目标到行为服务器。Tutorial Level: BEGINNER
Next Tutorial: 运行行为服务器和客户端
代码
首先,用你最喜欢的编辑器创建actionlib_tutorials/src/fibonacci_client.cpp,然后使用如下内容填充:
1 #include <ros/ros.h>
2 #include <actionlib/client/simple_action_client.h>
3 #include <actionlib/client/terminal_state.h>
4 #include <actionlib_tutorials/FibonacciAction.h>
5
6 int main (int argc, char **argv)
7 {
8 ros::init(argc, argv, "test_fibonacci");
9
10 // 创建行为客户端
11 // 成功会开启客户端创建自己的线程
12 actionlib::SimpleActionClient<actionlib_tutorials::FibonacciAction> ac("fibonacci", true);
13
14 ROS_INFO("Waiting for action server to start.");
15 //等待行为服务器开启
16 ac.waitForServer(); //will wait for infinite time
17
18 ROS_INFO("Action server started, sending goal.");
19 // 发送目标到行为服务器
20 actionlib_tutorials::FibonacciGoal goal;
21 goal.order = 20;
22 ac.sendGoal(goal);
23
24 //等待行为返回
25 bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
26
27 if (finished_before_timeout)
28 {
29 actionlib::SimpleClientGoalState state = ac.getState();
30 ROS_INFO("Action finished: %s",state.toString().c_str());
31 }
32 else
33 ROS_INFO("Action did not finish before the time out.");
34
35 //exit
36 return 0;
37 }
(源码可以在 教程包存储库 找到)
代码解释
现在,让我们分块的解释代码。
actionlib/client/simple_action_client.h 是行为库,从简单行为客户端实现。
actionlib/client/terminal_state.h 定义了目标可能的状态。
这个包含了从上述的Fibonacci.action中生成的行为消息。这是从 FibonacciAction.msg文件自动生成的头文件。想要知道更多关于消息定义的信息,请查阅msg界面.
行为客户端的定义模板,指定和行为服务器通信的消息类型。行为客户端的构造函数需要两个参数,包括用于连接的行为服务器名称和一个布尔类型的选项用于自动循环线程。如果你不喜欢使用线程(而且你想要actionlib在后台做'thread magic'),这对你来说是一个好的选项。这里的行为客户端通过传递服务名称和设置true的循环选项被构造出来。
如果行为服务端没有启动或运行,那么行为客户端会在进行下一步之前等待行为服务器。
这里创建了一个目标消息,设置目标值并且发送给行为服务端。
行为客户端会在进行下一步之前等待目标结束。等待超时(timeout)时间设定到30秒,这意味着30秒之后,如果目标还没有结束,函数会返回错误(false)。
如果目标在目标状态超时之前结束,那么会报告,否则会通知用户目标没有在给定的时间内结束。
编译
添加如下行到你的CMakeLists.txt文件:
add_executable(fibonacci_client src/fibonacci_client.cpp) target_link_libraries( fibonacci_client ${catkin_LIBRARIES} ) add_dependencies( fibonacci_client ${actionlib_tutorials_EXPORTED_TARGETS} )
然后编译:
cd %TOPDIR_YOUR_CATKIN_WORKSPACE% catkin_make source devel/setup.bash
rosbuild_add_executable(fibonacci_client src/fibonacci_client.cpp) rosbuild_link_boost(fibonacci_client thread)
运行行为客户端
在你编译成功之后,开启一个新的终端然后运行客户端:
$ rosrun actionlib_tutorials 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 [actionlib_tutorials/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 [actionlib_tutorials/FibonacciActionFeedback] 1 subscriber * /rosout [rosgraph_msgs/Log] 1 subscriber * /fibonacci/status [actionlib_msgs/GoalStatusArray] 1 subscriber * /fibonacci/result [actionlib_tutorials/FibonacciActionResult] 1 subscriber
或者你也可以看节点:
$ rxgraph
或者,如果使用Groovy版本,使用如下:
$ rqt_graph
这个展示了你的客户端正在订阅反馈(feedback)、状态(status)和期望的通道结果,以及会发布目标和期望取消通道,以上客户端表示工作正常。
连接服务器和客户端
对于使用你的行为的下一步,你需要按下Ctrl-C关闭行为客户端,并且 运行行为服务器和客户端。