32
32
33
33
import rospy
34
34
import rospkg
35
+ import roslib
35
36
36
37
from smach_msgs .msg import SmachContainerStatus ,SmachContainerInitialStatusCmd ,SmachContainerStructure
37
38
44
45
import StringIO
45
46
import colorsys
46
47
import time
48
+ import base64
47
49
48
50
import wxversion
49
51
if wxversion .checkInstalled ("2.8" ):
@@ -161,6 +163,14 @@ def update_structure(self, msg):
161
163
162
164
return needs_update
163
165
166
+ def _load_local_data (self , msg ):
167
+ """Unpack the user data"""
168
+ try :
169
+ local_data = pickle .loads (msg .local_data )
170
+ except KeyError :
171
+ local_data = pickle .loads (base64 .b64decode (msg .local_data .encode ('utf-8' )))
172
+ return local_data
173
+
164
174
def update_status (self , msg ):
165
175
"""Update the known userdata and active state set and return True if the graph needs to be redrawn."""
166
176
@@ -182,14 +192,14 @@ def update_status(self, msg):
182
192
# Unpack the user data
183
193
while not rospy .is_shutdown ():
184
194
try :
185
- self ._local_data ._data = pickle . loads (msg . local_data )
195
+ self ._local_data ._data = self . _load_local_data (msg )
186
196
break
187
197
except ImportError as ie :
188
198
# This will only happen once for each package
189
199
modulename = ie .args [0 ][16 :]
190
200
packagename = modulename [0 :modulename .find ('.' )]
191
201
roslib .load_manifest (packagename )
192
- self ._local_data ._data = pickle . loads (msg . local_data )
202
+ self ._local_data ._data = self . _load_local_data (msg )
193
203
194
204
# Store the info string
195
205
self ._info = msg .info
@@ -1061,4 +1071,4 @@ def main():
1061
1071
if __name__ == '__main__' :
1062
1072
rospy .init_node ('smach_viewer' ,anonymous = False , disable_signals = True ,log_level = rospy .INFO )
1063
1073
sys .argv = rospy .myargv ()
1064
- main ()
1074
+ main ()
0 commit comments