ROS Action¶
ROS Action概念¶
ROS Service会阻塞程序流,程序无法进行其它的工作,有时我们需要同时进行多个任务。
ROS Action可以满足要求,ROS Action提供程序的非阻塞执行。
Action是ROS Node的通信方式之一
Action server
向ROS系统广播指定action的Node,其它Node可以向该Node发出action目标请求
Action client
发出action目标请求的Node
Action通信的特点为:
- Action是类似于Service的通信机制,也是一种请求响应机制的通信方式,ROS的action通信通过Actionlib库实现
- Action主要弥补了service通信的一个不足,就是当机器人执行一个长时间的任务时,假如利用service通信方式,那么publisher会很长时间收不到反馈的reply,致使通信受阻。
- Action适合实现长时间的通信过程,且可以随时查看过程进度,也可以终止请求
Action通信的原理为:
- Action的工作原理是client-server模式,也是一个双向的通信模式
- 通信双方在ROS Action Protocol下通过消息进行数据的交流通信
- client和server为用户提供一个简单的API在客户端请求目标或在服务器端通过函数调用和回调来执行目标
下图是ROS Node Action通信的原理示意图,我们可以看到通信双方通过ROS Action Protocol实现通信。
Action的内容格式包含三个部分:目标、反馈、结果
目标(goal)
机器人执行一个动作,应该有明确的移动目标信息,包括一些参数的设定,如方向、角度、速度等等。从而使机器人完成动作任务。
目标在完成之前可被占用或被取消。
目标可处于ACTIVE、SUCCEEDED、ABORTED等不同的状态。
反馈(feedbac)
在动作进行的过程中,应该有实时的状态信息反馈给客户端,告诉客户端动作完成的状态,可以使客户端作出准确的判断去修正命令。
结果(result)
当动作完成时,服务端把运动的结果数据发送给客户端,使客户端得到本次动作的全部信息,例如机器人的运动时长、最终位姿等。
自定义Action类型¶
Action文件
- ROS通过action文件定义Action
- Action文件通常位于<ros_package_name>/action文件夹中
- Action文件的名字通常为<custom_message_type>.action
- Action类型包含goal、feedback、result三部分
自定义Action类型
现在,我们定义一个新的计算斐波那契数列的Action类型: Fibonacci
要求包含:
- Goal - 数列包含元素个数
- Result - 求解得到的数列
- Feedback - 已经列出的数列
我们可以通过以下指令创建这个新的Action类型:
首先创建action_demo Package:
catkin_create_pkg action_demo rospy std_msgs #在tr_tutorial_ws的src空间中
cd action_demo
mkdir action
touch action/Fibonacci.action
然后在新建的action文件中输入以下内容:
#goal definition
int32 order
---
#result definition
int32[] sequence
---
#feedback
int32[] sequence
编译构建自定义的Action类型
在上一部分我们定义了新的Action文件,新定义的Action经过编译构建之后才能在程序中使用。
首先修改package.xml文件,在package.xml文件中添加以下内容:
<build_depend>actionlib_msgs</build_depend>
<build_export_depend>actionlib_msgs</build_export_depend>
然后修改CMakeLists.txt文件,在CMakeLists.txt文件中相应的位置添加以下内容:
# 在find_package中添加actionlib_msgs
find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
actionlib_msgs
)
# 在add_action_files中添加Fibonacci.action
add_action_files(
FILES
Fibonacci.action
)
# 去掉generate_messages的注释,增加actionlib_msgs
generate_messages(
DEPENDENCIES
std_msgs
actionlib_msgs
)
# 在catkin_package中添加actionlib_msgs
catkin_package(
CATKIN_DEPENDS rospy std_msgs actionlib_msgs
)
随后切换到tr_tutorial_ws顶层目录执行编译构建:
catkin build
编译完成之后:
source devel/setup.bash
我们可以在devel/lib/python2.7/dist-packages/action_demo/msg路径下看到生成的Fibonacci Action相关的文件。
ROS Action示例¶
定义完Action之后,我们来看一下怎样使用SimpleActionServer和SimpleActionClient写一个简单的ROS应用,包含:
- 一个Action Server,提供计算斐波那契数列的服务
- 一个Action Client,发出计算斐波那契数列的请求
首先创建脚本文件用于存放示例代码:
roscd action_demo
mkdir scripts
touch scripts/fibonacci_server.py scripts/fibonacci_client.py
Action Server Node Demo
#! /usr/bin/env python
import rospy
import actionlib
import actionlib_tutorials.msg
class FibonacciAction(object):
# create messages that are used to publish feedback/result
_feedback = actionlib_tutorials.msg.FibonacciFeedback()
_result = actionlib_tutorials.msg.FibonacciResult()
def __init__(self, name):
self._action_name = name
self._as = actionlib.SimpleActionServer(self._action_name, actionlib_tutorials.msg.FibonacciAction, execute_cb=self.execute_cb, auto_start = False)
self._as.start()
def execute_cb(self, goal):
# helper variables
r = rospy.Rate(1)
success = True
# append the seeds for the fibonacci sequence
self._feedback.sequence = []
self._feedback.sequence.append(0)
self._feedback.sequence.append(1)
# publish info to the console for the user
rospy.loginfo('%s: Executing, creating fibonacci sequence of order %i with seeds %i, %i' % (self._action_name, goal.order, self._feedback.sequence[0], self._feedback.sequence[1]))
# start executing the action
for i in range(1, goal.order):
# check that preempt has not been requested by the client
if self._as.is_preempt_requested():
rospy.loginfo('%s: Preempted' % self._action_name)
self._as.set_preempted()
success = False
break
self._feedback.sequence.append(self._feedback.sequence[i] + self._feedback.sequence[i-1])
# publish the feedback
self._as.publish_feedback(self._feedback)
# this step is not necessary, the sequence is computed at 1 Hz for demonstration purposes
r.sleep()
if success:
self._result.sequence = self._feedback.sequence
rospy.loginfo('%s: Succeeded' % self._action_name)
self._as.set_succeeded(self._result)
if __name__ == '__main__':
rospy.init_node('fibonacci')
server = FibonacciAction(rospy.get_name())
rospy.spin()
Action Client Node Demo
#! /usr/bin/env python
from __future__ import print_function
import rospy
# Brings in the SimpleActionClient
import actionlib
# Brings in the messages used by the fibonacci action, including the
# goal message and the result message.
import actionlib_tutorials.msg
def fibonacci_client():
# Creates the SimpleActionClient, passing the type of the action
# (FibonacciAction) to the constructor.
client = actionlib.SimpleActionClient('fibonacci', actionlib_tutorials.msg.FibonacciAction)
# Waits until the action server has started up and started
# listening for goals.
client.wait_for_server()
# Creates a goal to send to the action server.
goal = actionlib_tutorials.msg.FibonacciGoal(order=20)
# Sends the goal to the action server.
client.send_goal(goal)
# Waits for the server to finish performing the action.
client.wait_for_result()
# Prints out the result of executing the action
return client.get_result() # A FibonacciResult
if __name__ == '__main__':
try:
# Initializes a rospy node so that the SimpleActionClient can
# publish and subscribe over ROS.
rospy.init_node('fibonacci_client_py')
result = fibonacci_client()
print("Result:", ', '.join([str(n) for n in result.sequence]))
except rospy.ROSInterruptException:
print("program interrupted before completion", file=sys.stderr)
我们可以尝试运行demo,在终端中会看到含20元素的斐波那契数列。
使用ROS Action开发ROS应用需要注意的内容:
- 我们当前使用的是Simple Action Server/Client,这是actionlib ROS package的通用action server的一种实现
- Simple Action Server/Client在同一时间只支持一个目标的非阻塞运行
- 新的目标到达会抢占已经激活的目标
- 我们可以实现自己的Action Server支持多目标的运行
ROS Action练习¶
我们已经完成了Action Server、Client的构建及定义新的Action类型,接下来我们进行一个小练习,构建一个简单的ROS应用:
- 包含一个Action Server,一个Action Client
- Action Server提供计数服务,计数完成之后反馈计数成功
- Action Client发出计数请求
Counter Action定义-示例:
uint32 num_counts
---
string result_message
---
uint32 counts_elapsed
ROS Action练习示例-Server:
#! /usr/bin/env python
import rospy
import actionlib
from action_demo.msg import CounterWithDelayAction, CounterWithDelayFeedback, CounterWithDelayResult
class CounterWithDelayActionClass(object):
# create messages that are used to publish feedback/result
_feedback = CounterWithDelayFeedback()
_result = CounterWithDelayResult()
def __init__(self, name):
# This will be the name of the action server which clients can use to connect to.
self._action_name = name
# Create a simple action server of the newly defined action type and
# specify the execute callback where the goal will be processed.
self._as = actionlib.SimpleActionServer(self._action_name, CounterWithDelayAction, execute_cb=self.execute_cb, auto_start = False)
# Start the action server.
self._as.start()
rospy.loginfo("Action server started...")
def execute_cb(self, goal):
# Define frequency
r = rospy.Rate(1)
# Variable to decide the final state of the action server.
success = True
# start executing the action
for counter_idx in range(0, goal.num_counts):
# check that preempt has not been requested by the client
if self._as.is_preempt_requested():
rospy.loginfo('%s: Preempted' % self._action_name)
self._as.set_preempted()
success = False
break
# publish the feedback
self._feedback.counts_elapsed = counter_idx
self._as.publish_feedback(self._feedback)
# Wait for counter_delay s before incrementing the counter.
r.sleep()
if success:
self._result.result_message = "Successfully completed counting."
rospy.loginfo('%s: Succeeded' % self._action_name)
self._as.set_succeeded(self._result)
if __name__ == '__main__':
# Initialize a ROS node for this action server.
rospy.init_node('counter_with_delay')
# Create an instance of the action server here.
server = CounterWithDelayActionClass(rospy.get_name())
rospy.spin()
ROS Action练习示例-Client:
#! /usr/bin/env python
from __future__ import print_function
import rospy
# Brings in the SimpleActionClient
import actionlib
# Brings in the messages used by the CounterWithDelay action, including the
# goal message and the result message.
from action_demo.msg import CounterWithDelayAction, CounterWithDelayGoal, CounterWithDelayResult
def counter_with_delay_client():
# Creates the SimpleActionClient, passing the type of the action
# (CounterWithDelayAction) to the constructor.
client = actionlib.SimpleActionClient('counter_with_delay', CounterWithDelayAction)
# Waits until the action server has started up and started
# listening for goals.
rospy.loginfo("Waiting for action server to come up...")
client.wait_for_server()
num_counts = 10
# Creates a goal to send to the action server.
goal = CounterWithDelayGoal(num_counts)
# Sends the goal to the action server.
client.send_goal(goal)
rospy.loginfo("Goal has been sent to the action server.")
# Waits for the server to finish performing the action.
# client.wait_for_result()
for count_idx in range(0, 10):
print("I am doing other things while the goal is being serviced by the server")
rospy.sleep(1.5)
# Prints out the result of executing the action
return client.get_result() # A CounterWithDelayResult
if __name__ == '__main__':
try:
# Initializes a rospy node so that the SimpleActionClient can
# publish and subscribe over ROS.
rospy.init_node('counter_with_delay_ac')
result = counter_with_delay_client()
rospy.loginfo(result.result_message)
except rospy.ROSInterruptException:
print("program interrupted before completion", file=sys.stderr)
- 更多关于ROS Action的内容可以参考以下链接:
- http://wiki.ros.org/actionlib