抢占需要在并发容器里面实现,并发容器里面包含多个状态,我们分成两类:抢占状态与被抢占状态
抢占的实现原理:
def child_cb(outcome_map):
rospy.loginfo('excute child call back')
return True
sm_con = smach.Concurrence(outcomes=['outcome4','preempted'],
default_outcome='outcome4',
outcome_map={'preempted':{ 'FOO':'outcome1','BAR':'preempted'},
'outcome4':{'BAR':'outcome2'}},
child_termination_cb = child_cb)
# define state Bar
class Bar(smach.State):
def __init__(self):
smach.State.__init__(self, outcomes=['outcome2','preempted'])
def execute(self, userdata):
rospy.loginfo('Executing state BAR')
if self.preempt_requested():
self.service_preempt()
return 'preempted'
rospy.sleep(50)
return 'outcome2'
set_preempt_handler(你的状态机名)
全部代码:
#!/usr/bin/env python3
# 在并发状态机里面测试状态抢占功能
import rospy
import smach
import smach_ros
from smach_ros import ServiceState, SimpleActionState, IntrospectionServer,set_preempt_handler, MonitorState
# define state Foo
class Foo(smach.State):
def __init__(self):
smach.State.__init__(self, outcomes=['outcome1'])
self.counter = 0
def execute(self, userdata):
rospy.loginfo('Executing state FOO')
rospy.sleep(1)
return 'outcome1'
# define state Bar
class Bar(smach.State):
def __init__(self):
smach.State.__init__(self, outcomes=['outcome2','preempted'])
def execute(self, userdata):
rospy.loginfo('Executing state BAR')
if self.preempt_requested():
self.service_preempt()
return 'preempted'
# n=1
# while n<50:
# rospy.sleep(1)
# rospy.loginfo('Do something')
# n+=1
# Check for preempt
rospy.sleep(50)
return 'outcome2'
# define state Bas
class Bas(smach.State):
def __init__(self):
smach.State.__init__(self, outcomes=['outcome3'])
def execute(self, userdata):
rospy.loginfo('Executing state BAS')
return 'outcome3'
def child_cb(outcome_map):
rospy.loginfo('excute child call back')
return True
def main():
rospy.init_node('smach_example_state_machine')
# Create the top level SMACH state machine
sm_top = smach.StateMachine(outcomes=['outcome6'])
# Open the container
with sm_top:
smach.StateMachine.add('BAS', Bas(),
transitions={'outcome3':'CON'})
# Create the sub SMACH state machine
sm_con = smach.Concurrence(outcomes=['outcome4','preempted'],
default_outcome='outcome4',
outcome_map={'preempted':{ 'FOO':'outcome1','BAR':'preempted'},
'outcome4':{'BAR':'outcome2'}},
child_termination_cb = child_cb)
# Open the container
with sm_con:
# Add states to the container
smach.Concurrence.add('FOO', Foo())
smach.Concurrence.add('BAR', Bar())
smach.StateMachine.add('CON', sm_con,
transitions={'outcome4':'CON',
'preempted':'outcome6'})
# Create and start the introspection server
sis = smach_ros.IntrospectionServer('server_name', sm_top, '/SM_ROOT')
sis.start()
# sm_top.request_preempt()
set_preempt_handler(sm_top)
outcome = sm_top.execute()
# Wait for ctrl-c to stop the application
rospy.spin()
sis.stop()
if __name__ == '__main__':
main()
该例子跑出来的效果:
能够完成Foo对Bar的抢占,不抢占的话会反复在CON和Bar状态里循环,但是Foo要等Bar执行完毕才去抢占。
这样是不行的
必须把状态2和状态3打包成一个整体,打包在sm_sub1里面
def excute
,状态机咋搞?层级数目超过教程例子的状态机就不建议参考使用SMACH,在确定要使用SMACH的情况下,建议在状态机设计时尽可能贴近SMACH教程的架构。