新建 action messages
在新建action之前,有必要先定义好什么是目标goal,结果result,反馈信息feedback。action信息有 .action 文件自动生成,更多action文件的信息可见下面的文件actionlib. 文件定义了goal, result, feedback主题的类型与格式,在目录中新建如下文件learning_actionlib/action/Fibonacci.action,内容复制如下的代码:
#goal definition
int32 order
---
#result definition
int32[] sequence
---
#feedback
int32[] sequence
为了自动生成一系列message文件,需要在CMakeLists.txt中变更如下的语句:
.
在 CMakeLists.txt中find_package行更改为下面内容:
find_package(catkin REQUIRED COMPONENTS actionlib_msgs)
- (actionlib_msgs包括了message_generation,因此不需要再列出message_generation组件).
增加使用的action文件:
add_action_files( DIRECTORY action FILES fac.action)
添加actionlib_msgs到 generate_messages:
:
generate_messages( DEPENDENCIES actionlib_msgs std_msgs
添加actionlib_msgs到catkin_package:
catkin_package( CATKIN_DEPENDS actionlib_msgs)
- (catkin_packag只能添加CATKIN_DEPEND到actionlib_msgs
接下来可以开始自动生成msg:
$ cd ../.. # 到工作空间
$ catkin_make
$ ls devel/share/learning_actionlib/msg/
facActionFeedback.msg facAction.msg facFeedback.msgfacResult.msg facActionGoal.msg facActionResult.msg facGoal.msg
$ ls devel/include/learning_actionlib/
facActionFeedback.h facAction.h facFeedback.h facResult.hfacActionGoal.h facActionResult.h facGoal.h
可以使用actionlib_msgs包中的genaction.py脚本手动生成msg。
写一个简单的服务端
代码阳历在 actionlib_tutorials 软件包中,可以先阅读 actionlib 软件包.
代码
代码在actionlib_tutorials/simple_action_servers/fac_server.py中:
#! /usr/bin/env python
import roslib; roslib.load_manifest('actionlib_tutorials')
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 xrange(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')
FibonacciAction(rospy.get_name())
rospy.spin()
运行服务端程序
python fibonacci_server.py