(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

简单状态机

Description: 本教程介绍如何将一个简单的状态机与两个状态组合在一起。

Tutorial Level: BEGINNER

Next Tutorial: 传递用户数据

所有下面的示例都可以在不修改的情况下运行。它们可以在示例目录中的smach_tutorials包中找到。每个文件头部的注释大致显示了运行脚本的输出应该是什么样的。

state_machine2.png

https://raw.githubusercontent.com/eacousineau/executive_smach_tutorials/hydro-devel/smach_tutorials/examples/state_machine2.py

   1 #!/usr/bin/env python
   2 
   3 import roslib; roslib.load_manifest('smach_tutorials')
   4 import rospy
   5 import smach
   6 import smach_ros
   7 
   8 # define state Foo
   9 class Foo(smach.State):
  10     def __init__(self):
  11         smach.State.__init__(self, outcomes=['outcome1','outcome2'])
  12         self.counter = 0
  13 
  14     def execute(self, userdata):
  15         rospy.loginfo('Executing state FOO')
  16         if self.counter < 3:
  17             self.counter += 1
  18             return 'outcome1'
  19         else:
  20             return 'outcome2'
  21 
  22 
  23 # define state Bar
  24 class Bar(smach.State):
  25     def __init__(self):
  26         smach.State.__init__(self, outcomes=['outcome1'])
  27 
  28     def execute(self, userdata):
  29         rospy.loginfo('Executing state BAR')
  30         return 'outcome1'
  31         
  32 
  33 
  34 
  35 
  36 def main():
  37     rospy.init_node('smach_example_state_machine')
  38 
  39     # Create a SMACH state machine
  40     sm = smach.StateMachine(outcomes=['outcome4'])
  41 
  42     # Open the container
  43     with sm:
  44         # Add states to the container
  45         smach.StateMachine.add('FOO', Foo(), 
  46                                transitions={'outcome1':'BAR', 'outcome2':'outcome4'})
  47         smach.StateMachine.add('BAR', Bar(), 
  48                                transitions={'outcome1':'FOO'})
  49 
  50     # Execute SMACH plan
  51     outcome = sm.execute()
  52 
  53 
  54 
  55 if __name__ == '__main__':
  56     main()

Wiki: cn/smach/Tutorials/Simple State Machine (last edited 2018-03-10 06:18:10 by Playfish)