## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= ## descriptive title for the tutorial ## title = 在状态间传递用户数据 ## multi-line description to be displayed in search ## description = 这个教程将教会你如何从一个状态(机)传递数据到下一个状态(机)。 ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link=[[cn/smach/Tutorials/Create a hierarchical state machine|创建一个分级状态机]] ## next.1.link= ## what level user is this tutorial for ## level= BeginnerCategory ## keywords = #################################### <> <> == 指定用户数据 == 一个状态可能需要一些输入数据来完成它的工作,或者它可能有一些输出数据,它想要提供给其他状态。状态的输入和输出数据称为'''userdata'''。当你构造一个状态时,你可以指定它需要/提供的用户数据字段的名称。 {{{#!python class Foo(smach.State): def __init__(self, outcomes=['outcome1', 'outcome2'], input_keys=['foo_input'], output_keys=['foo_output']) def execute(self, userdata): # Do something with userdata if userdata.foo_input == 1: return 'outcome1' else: userdata.foo_output = 3 return 'outcome2' }}} * '''input_keys'''列表列出了一个状态需要运行的所有输入。一个状态声明它期望在用户数据中包含这些字段。execute方法提供了一个userdata 结构体的副本。状态可以从它在input_keys列表中枚举所有userdata字段中读取,但它不能写入任何这些字段。 * '''output_keys'''列表列出了一个状态提供的所有输出。在output_keys列表中,状态可以写入所有枚举的用户数据结构体里的字段。 ''' /!\ 注意: '''通过input_keys从userdata获得的对象被包装为不变性,因此一个状态不能调用这些对象上的方法。如果需要一个可变的输入对象,则必须在input_keys和output_keys中指定相同的密钥。如果你没有传递对象,或者不需要调用方法或修改它们,那么应该在input_keys和output_keys中使用惟一名称,以避免混淆和潜在的错误。 {{attachment:user_data_single.png||width="250"}} 状态的接口由其结果、输入键和输出键来定义。 == 连接用户数据 == 当向状态机添加状态时,还需要连接用户数据字段,以便允许状态之间传递数据。例如,如果状态FOO生成'foo_output',而状态BAR需要'bar_input',那么你可以使用名称映射将这两个用户数据端口连接在一起: {{{#!python sm_top = smach.StateMachine(outcomes=['outcome4','outcome5'], input_keys=['sm_input'], output_keys=['sm_output']) with sm_top: smach.StateMachine.add('FOO', Foo(), transitions={'outcome1':'BAR', 'outcome2':'outcome4'}, remapping={'foo_input':'sm_input', 'foo_output':'sm_data'}) smach.StateMachine.add('BAR', Bar(), transitions={'outcome2':'FOO'}, remapping={'bar_input':'sm_data', 'bar_output1':'sm_output'}) }}} 重新映射字段将状态的in/output_key映射到状态机的userdata字段。所以当你重新映射'x':'y'的时候: * x 需要是状态的input_key或output_key。 * y 将自动成为状态机的用户数据的一部分。 /!\ 注意,当你的状态中使用的用户数据名称与状态机使用的用户数据名称相同时,重新映射是''不需要的''。然而,remapping使连接非常明确,因此''建议''总是指定重新映射,甚至"remapping={'a':'a'}"。 === 状态间传递数据 === 我们可以使用重新映射机制将数据从状态FOO传递到状态BAR。为了实现这一点,我们需要在添加FOO时重新映射,并在添加BAR时重新映射: * FOO: remapping={'foo_output':'sm_user_data'} * BAR: remapping={'bar_input':'sm_user_data'} === 在状态机和状态间传递数据 === 我们还可以使用映射机制将数据从状态BAR传递到包含BAR的状态机。如果'sm_output'是状态机的输出键: * BAR: remapping={'bar_output':'sm_output'} 或者,相反的,我们可以将数据从状态机传递到状态FOO。如果“sm_input”是状态机的输入键: * FOO: remapping={'foo_input':'sm_input'} {{attachment:user_data.png||width="650"}} == 示例 == 你可以在[[executive_smach_tutorials]]包中找到一个完整的可运行的示例。 {{{#!wiki <> }}} 运行示例: {{{ $ roscd smach_tutorials $ ./examples/user_data2.py }}} ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE ## LearningSMACHCategory