SMACH专题(三)----几种State类型

  状态机提供了若干种状态,包括了Generic StateCBStateSimpleActionState (ROS)ServiceState (ROS)MonitorState (ROS)。下面分别介绍它们的用法和例子。

一、CBState回调状态

  将一个函数封装成状态,这种状态成为回调状态。这种函数非类中的函数,而是一般的函数。下面是一个例子:

 #!/usr/bin/env python
# license removed for brevity import rospy
from std_msgs.msg import String
import math
import random
from smach import CBState, StateMachine
from smach_ros import IntrospectionServer
import smach @smach.cb_interface(
output_keys=['xyz'],
outcomes=['outcome1','outcome2'])
def fun_cb(ud,x0, x, y, z):
'''
callback function, which is called in CBState way, it seems to be used by
function, but the class'funtion
'''
#x0 is the value of cb_args=[10], equal to 10
dist = math.sqrt(x0*x0+x*x+y*y+z*z+100*random.random())
ud.xyz = dist
if dist > 10:
return 'outcome1'
else:
return 'outcome2' class Test_CbState():
def __init__(self):
rospy.init_node('smach_example_callback_state')
self.sample_name = "cbstate" def test(self):
'''
test Callback State Machine
'''
self.sm = StateMachine(outcomes = ['outcome3'])
with self.sm:
StateMachine.add('Test_CB',CBState(fun_cb,
cb_args=[10],
cb_kwargs={'x':1,'y':2,'z':3}),
{'outcome1':'outcome3','outcome2':'Test_CB'})
sis = IntrospectionServer('test_cb_state', self.sm, '/SM_ROOT')
sis.start() self.sm.execute('Test_CB') rospy.spin()
sis.stop() if __name__ == '__main__':
'''
main funtion
'''
test_sm_cbstate = Test_CbState()
test_sm_cbstate.test()

  状态图,如下图所示:

SMACH专题(三)----几种State类型

  参考资料:

    [1]. CBState

上一篇:angular学习笔记(二十八)-$http(6)-使用ngResource模块构建RESTful架构


下一篇:解决solr 请求参数过长报错too many boolean clauses Exception