用户数据UserData类和重映射Remapper类包含在smach中的user_data.py文件中实现,该博文主要介绍其原理和例子
- UserData主要用于状态之间的数据传递,包括数据的输入input_keys和输出output_keys。用户数据做为状态的execute函数的参数来使用。而输入和输出的初始化在状态的__init__中进行初始化。数据结构可以表示为树状:
UserData
-- input_keys
--output_keys
- Rempaper主要用于用户数据中的输入input_keys和输出键output_keys的名字重映射。和消息的重映射的思路相同。
进一步关于UserData如何在状态之间传递和指定输入输出键的,请参考如下的资料:
原理:The principle of Passing User Data between States
例子:The example of Passing User Data between States
1、源码注释
具体的中文翻译解释和一些额外的注释,请看如下的实现代码:
import threading
import copy import smach __all__ = ['UserData','Remapper']#用"__all__"导出UserData,Remapper两个类 #用户数据,用于状态之间的传递,输入或输出
class UserData(object):
"""SMACH user data structure."""
'''SMACH 用户数据结构'''
def __init__(self):
self._data = {}
self._locks = {}
self.__initialized = True def update(self, other_userdata):
"""Combine this userdata struct with another.
This overwrites duplicate keys with values from C{other_userdata}.
"""
'''将外加的用户数据和原有的用户数据合并,重复关键字的会更新相应的值'''
# Merge data
# 合并数据
self._data.update(other_userdata._data) def extract(self, keys, remapping):
ud = UserData()
reverse_remapping = {remapping[k]: k for k in remapping}
if len(reverse_remapping) != len(remapping):
smach.logerr("SMACH userdata remapping is not one-to-one: " + str(remapping))
for k in keys:
rmk = k
if k in reverse_remapping:
rmk = reverse_remapping[k]
ud[rmk] = copy.copy(self[k])
return ud def merge(self, ud, keys, remapping):
for k in keys:
rmk = k
if k in remapping:
rmk = remapping[k]
self[rmk] = copy.copy(ud[k]) def __getitem__(self, key):
return self.__getattr__(key) def __setitem__(self, key, item):
self._data[key] = item def keys(self):
return list(self._data.keys()) def __contains__(self,key):
return key in self._data def __getattr__(self, name):
"""Override getattr to be thread safe."""
'''重写getattr是线程安全的'''
if name[0] == '_':
return object.__getattr__(self, name)
if not name in self._locks.keys():
self._locks[name] = threading.Lock() try:
with self._locks[name]:
temp = self._data[name]
except:
smach.logerr("Userdata key '%s' not available. Available keys are: %s" % (name, str(list(self._data.keys()))))
raise KeyError() return temp def __setattr__(self, name, value):
"""Override setattr to be thread safe."""
'''重写setattr是线程安全的'''
# If we're still in __init__ don't do anything special
if name[0] == '_' or '_UserData__initialized' not in self.__dict__:
return object.__setattr__(self, name, value) if not name in self._locks.keys():
self._locks[name] = threading.Lock() self._locks[name].acquire()
self._data[name] = value
self._locks[name].release() # Const wrapper
def get_const(obj):
"""Get a const reference to an object if it has "user-defined" attributes."""
'''如果obj有“user-defined”属性,那么返回obj的一个常引用'''
if hasattr(obj,'__dict__'):
smach.logdebug("Making const '%s'" % str(obj))
return Const(obj)
else:
return obj #object对象常量化
class Const(object):
"""Wrapper that treats "user-defined" fields as immutable. This wrapper class is used when user data keys are specified as input keys,
but not as output keys.
""" '''一个对object的封装器,将object中的“user-defined”的域设置为不可改变,即只读 当用户数据的keys中被指定了input keys,但没有 output keys时,会用到这个封装器。
'''
def __init__(self, obj):
smach.logdebug("Making const '%s'" % str(obj))
self._obj = obj
self.__initialized = True def __getattr__(self, name):
smach.logdebug("Getting '%s' from const wrapper." % name)
attr = getattr(self._obj,name)
return get_const(attr) def __getitem__(self, name):
smach.logdebug("Getting '%s' from const wrapper." % name)
attr = self._obj[name]
return get_const(attr) def __setattr__(self, name, value):
if '_const__initialized' not in self.__dict__:
return object.__setattr__(self, name, value)
smach.logerr("Attempting to set '%s' but this member is read-only." % name)
raise TypeError() def __delattr__(self, name):
smach.logerr("Attempting to delete '%s' but this member is read-only." % name)
raise TypeError() #用户数据结构的键值重映射
class Remapper(object):
"""Key-remapping proxy to a SMACH userdata structure."""
'''对Smach 用户数据结构的一个键值重映射代理'''
def __init__(self, ud, input_keys=[], output_keys=[], remapping={}):
self._ud = ud
self._input = input_keys
self._output = output_keys
self._map = remapping
self.__initialized = True def _remap(self, key):
"""Return either the key or it's remapped value."""
'''返回key‘s value或者remapped’s value'''
if key in self._map:
return self._map[key]
return key def update(self, other_userdata):
self._ud.update(other_userdata) def __getitem__(self, key):#“__“两个下划线表示内置函数,类似inline?;“_“一个下划线表示私有函数
if key not in self._input:
raise smach.InvalidUserCodeError("Reading from SMACH userdata key '%s' but the only keys that were declared as input to this state were: %s. This key needs to be declaread as input to this state. " % (key, self._input))
if key not in self._output:
return get_const(self._ud.__getitem__(self._remap(key)))
return self._ud.__getitem__(self._remap(key)) def __setitem__(self, key, item):
if key not in self._output:
smach.logerr("Writing to SMACH userdata key '%s' but the only keys that were declared as output from this state were: %s." % (key, self._output))
return
self._ud.__setitem__(self._remap(key),item) def keys(self):
return [self._remap(key) for key in self._ud.keys() if key in self._input] def __contains__(self,key):
if key in self._input:
return self._remap(key) in self._ud
else:
return False def __getattr__(self, name):
if name[0] == '_':
return object.__getattr__(self, name)
if name not in self._input:
raise smach.InvalidUserCodeError("Reading from SMACH userdata key '%s' but the only keys that were declared as input to this state were: %s. This key needs to be declaread as input to this state. " % (name, self._input))
if name not in self._output:
return get_const(getattr(self._ud, self._remap(name)))
return getattr(self._ud, self._remap(name)) def __setattr__(self, name, value):
if name[0] == '_' or '_Remapper__initialized' not in self.__dict__:
return object.__setattr__(self, name, value)
if name not in self._output:
smach.logerr("Writing to SMACH userdata key '%s' but the only keys that were declared as output from this state were: %s." % (name, self._output))
return None
setattr(self._ud, self._remap(name), value)
2、例子-用户数据和键值重映射
参考ROS的smach例程,例子:The example of Passing User Data between States
#!/usr/bin/env python import roslib; roslib.load_manifest('smach_tutorials')
import rospy
import smach
import smach_ros # define state Foo
class Foo(smach.State):
def __init__(self):
smach.State.__init__(self,
outcomes=['outcome1','outcome2'],
input_keys=['foo_counter_in'],#键初始化
output_keys=['foo_counter_out']) def execute(self, userdata):#用户数据做为参数使用
rospy.loginfo('Executing state FOO')
if userdata.foo_counter_in < 3:
userdata.foo_counter_out = userdata.foo_counter_in + 1
return 'outcome1'
else:
return 'outcome2' # define state Bar
class Bar(smach.State):
def __init__(self):
smach.State.__init__(self,
outcomes=['outcome1'],
input_keys=['bar_counter_in'])#键对初始化 def execute(self, userdata):#用户数据做为参数使用
rospy.loginfo('Executing state BAR')
rospy.loginfo('Counter = %f'%userdata.bar_counter_in)
return 'outcome1' def main():
rospy.init_node('smach_example_state_machine') # Create a SMACH state machine
sm = smach.StateMachine(outcomes=['outcome4'])
sm.userdata.sm_counter = 0 # Open the container
with sm:
# Add states to the container
smach.StateMachine.add('FOO', Foo(),
transitions={'outcome1':'BAR',
'outcome2':'outcome4'},
remapping={'foo_counter_in':'sm_counter',
'foo_counter_out':'sm_counter'})
smach.StateMachine.add('BAR', Bar(),
transitions={'outcome1':'FOO'},
remapping={'bar_counter_in':'sm_counter'})#键值重映射,重映射的名字可以根据具体的业务指定,这样更易于理解 # Execute SMACH plan
outcome = sm.execute() if __name__ == '__main__':
main()