36 import roslib; roslib.load_manifest(
'rosjson')
46 _JSON_ESCAPE = {
'\\':
r'\\',
'"':
'\\"',
'\b':
r'\b',
'\f':
r'\f',
'\n':
r'\n',
'\r':
r'\r',
'\t':
r'\t'}
54 buff = cStringIO.StringIO()
59 buff.write(_JSON_ESCAPE[c])
64 return buff.getvalue()
65 elif type(v)
in (int, float, long):
67 elif type(v)
in (list, tuple):
74 elif isinstance(v, rospy.Message):
76 elif isinstance(v, (genpy.rostime.Time, genpy.rostime.Duration)):
89 if not isinstance(msg, rospy.Message):
90 raise ROSJSONException(
"not a valid rospy Message instance: %s"%msg.__class__.__name__)
91 buff = cStringIO.StringIO()
93 buff.write(
','.join([
'"%s": %s'%(f,
value_to_json(getattr(msg, f)))
for f
in msg.__slots__]))
95 return buff.getvalue()
def value_to_json(v)
Convert value to JSON representation.
def ros_message_to_json(msg)
Convert ROS message to JSON representation.