ROS节点通信(三)action

1、说明

ROS中的action也是节点通信的一种方式,其和service-client的不同点在于,service-client是一问一答模式,而action则多了一个反馈机制,即服务端不间断给客户端反馈

2、代码示例

跳过创建工作区和功能包步骤

2.1、定义数据结构

action定义的数据结构分成三个部分,中间用 隔开,按照顺序如下:

2.1.1、goal

为了使action完成任务,引入一个目标概念,由客户端发送到服务端

2.1.4、result

结果由服务端发送给客户端,在完成 goal 之后,发送的任务结果

2.1.3、feedback

反馈为服务端发送到客户端,高度客户端,当前任务的进展

TestData.action

#请求的数据,一般由客户端发送给服务端
uint32 id

#请求结果,一般由服务端发送给客户端
uint32 total

#反馈的消息内容,一般由服务端不间断发送到客户端
float32 percent

.action 文件默认保存在 action 目录下

对于该文件,会生成7个消息类型,以便客户端和服务端通信,这些类型由 genaction.py 生成:

  1. TestDataAction.msg
  2. TestDataActionGoal.msg
  3. TestDataActionResult.msg
  4. TestDataActionFeedback.msg
  5. TestDataGoal.msg
  6. TestDataResult.msg
  7. TestDataFeedback.msg

2.2、服务端

#include <ros/ros.h>
#include <test_action/TestDataAction.h>
#include <actionlib/server/simple_action_server.h> typedef actionlib::SimpleActionServer<test_action::TestDataAction> Server; void execute(const test_action::TestDataGoalConstPtr& goal, Server* server)
{

ros::Rate rate(1);<br/>
test_action::TestDataFeedback feedback;

ROS_INFO(“Dishwasher %d is working.”, goal-&gt;id); for(int index = 1; index &lt;= 10; index++)

{<br/>
    feedback.percent = index * 10;<br/>
    server-&gt;publishFeedback(feedback);<br/>
    rate.sleep();<br/>
}

ROS_INFO(“Dishwasher %d finish working.”, goal-&gt;id);

server-&gt;setSucceeded();<br/>

} int main(int argc, char** argv)
{

ros::init(argc, argv, &#34;test_action_service&#34;);<br/>
ros::NodeHandle handle;<br/>
//构建一个action服务,第二个参数是服务的名称,客户端需要根据这个唯一的名称进行连接<br/>
//最后一个参数表示是否构建完成之后就开始运行,一般应该设置为false,并在构建完成之后使用start()方法开始<br/>
Server server(handle, &#34;do_action&#34;,<br/>
              boost::bind(&amp;execute, _1, &amp;server), false);<br/>
server.start();<br/>
ros::spin();<br/>
return 0;<br/>

}

2.3、客户端

#include &lt;ros/ros.h&gt;
#include &lt;test_action/TestDataAction.h&gt;
#include &lt;actionlib/client/simple_action_client.h&gt; typedef actionlib::SimpleActionClient&lt;test_action::TestDataAction&gt; Client; //完成调用回调
void doneCb(const actionlib::SimpleClientGoalState& state,

        const test_action::TestDataResultConstPtr&amp; result)<br/>

{

ROS_INFO(&#34;The dishes are now clean&#34;);<br/>
ros::shutdown();<br/>

} void activeCb()
{

ROS_INFO(&#34;goal just went active&#34;);<br/>

} //反馈
void feedbackCb(const test_action::TestDataFeedbackConstPtr& feedback)
{

ROS_INFO(&#34;percent: %f&#34;, feedback-&gt;percent);<br/>

} int main(int args, char** argv)
{

ros::init(args, argv, &#34;test_action_client&#34;);<br/>
Client client(&#34;do_action&#34;, true);<br/>
ROS_INFO(&#34;waiting for action server to start&#34;);<br/>
client.waitForServer();<br/>
ROS_INFO(&#34;action server started, sending goal&#34;);

test_action::TestDataGoal goal;

goal.id = 9;//填入goal<br/>
//客户端发送目标,后三个是各个阶段的回调,分别在完成时、通信刚激活时和反馈过程中<br/>
client.sendGoal(goal, &amp;doneCb, &amp;activeCb, &amp;feedbackCb);<br/>
ros::spin();

return 0;
}

2.4、构建配置

CMakeLists.txt需要添加以下包依赖

find_package(catkin REQUIRED genmsg actionlib_msgs actionlib)
add_action_files(DIRECTORY action FILES DoDishes.action)
generate_messages(DEPENDENCIES actionlib_msgs)

其中,genmsgactionlib_msgs 是构建 .action 文件的时候需要的依赖,actionlib 是编译的时候需要的依赖

packages.xml 配置

&lt;buildtool_depend&gt;catkin&lt;/buildtool_depend&gt;
&lt;buildtool_depend&gt;genmsg&lt;/buildtool_depend&gt;
&lt;build_export_depend&gt;actionlib_msgs&lt;/build_export_depend&gt;
&lt;build_depend&gt;actionlib&lt;/build_depend&gt;
&lt;build_depend&gt;actionlib_msgs&lt;/build_depend&gt;
&lt;exec_depend&gt;actionlib&lt;/exec_depend&gt;
&lt;exec_depend&gt;actionlib_msgs&lt;/exec_depend&gt;

2.5、结果

服务端:

[ INFO] [1621921903.942496821]: Dishwasher 9 is working.
[ INFO] [1621921913.942535907]: Dishwasher 9 finish working.

客户端:

[ INFO] [1621921903.728245862]: waiting for action server to start
[ INFO] [1621921903.941538934]: action server started, sending goal
[ INFO] [1621921903.942692392]: goal just went active
[ INFO] [1621921903.943088999]: percent: 10.000000
[ INFO] [1621921904.942911217]: percent: 20.000000
[ INFO] [1621921905.942921653]: percent: 30.000000
[ INFO] [1621921906.942895095]: percent: 40.000000
[ INFO] [1621921907.942843906]: percent: 50.000000
[ INFO] [1621921908.942901935]: percent: 60.000000
[ INFO] [1621921909.942896131]: percent: 70.000000
[ INFO] [1621921910.942844776]: percent: 80.000000
[ INFO] [1621921911.942889215]: percent: 90.000000
[ INFO] [1621921912.942941318]: percent: 100.000000
[ INFO] [1621921913.943146759]: The dishes are now clean