Go to the documentation of this file.00001 import roslib; roslib.load_manifest("cassandra_ros")
00002 import rospy
00003
00004 from rospy_message_converter import json_message_converter
00005 import genpy
00006
00007 import pycassa
00008 import simplejson as json
00009
00010 from CassandraTopic_ import *
00011
00012 class CassandraTopic_string(CassandraTopic_):
00013 def __init__(self, MsgClass):
00014 CassandraTopic_.__init__(MsgClass)
00015
00016 def getColumnValidationClasses(self):
00017 return {'string' : pycassa.UTF8_TYPE}
00018
00019 def encode(self, msg):
00020
00021 return {'string' : json_message_converter.convert_json_to_ros_message(self.MsgClass()._type, msg)}
00022
00023 def decode(self, data):
00024 _dict = json.loads(data['string'])
00025 msg = self.MsgClass()
00026 msg = self._dict_to_ros(_dict, msg)
00027 return msg
00028
00029 def _dict_to_value(self, _dict, _slot, _type):
00030
00031 if isinstance(_slot, (str, int, float, bool)):
00032 return _dict
00033
00034 elif isinstance(_slot, (list, dict, tuple)):
00035 msg = []
00036 if _type in ('bool[]', 'int8[]', 'uint8[]', 'int16[]', 'uint16[]', 'int32[]', 'uint32[]',
00037 'int64[]', 'uint64[]', 'float32[]', 'float64[]', 'string[]'):
00038 msg = _dict
00039 else:
00040 _type = _type.replace("[]","")
00041 _slot = genpy.message.get_message_class(_type)()
00042 for elem in _dict:
00043 msg.append( self._dict_to_ros( elem, _slot) )
00044
00045 return msg
00046 elif isinstance(_slot, (genpy.rostime.Time, genpy.rostime.Duration)):
00047 t = rospy.Time()
00048 secs = int(_dict)
00049 nsecs= (_dict - float(secs))*10**9
00050 t.set(secs, nsecs)
00051 return t
00052 elif isinstance(_slot, rospy.Message):
00053 return self._dict_to_ros(_dict, _slot)
00054 else:
00055 raise RosCassandraTranspileException("unknown type: %s"%type(_slot))
00056
00057 def _dict_to_ros(self, _dict, msg):
00058
00059 for i in range(len(msg.__slots__)):
00060 _slot = msg.__slots__[i]
00061 _type = msg._slot_types[i]
00062
00063 setattr(msg,
00064 _slot,
00065 self._dict_to_value( _dict[_slot],
00066 getattr(msg, _slot),
00067 _type))
00068
00069 return msg