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


cassandra_ros
Author(s): André Dietrich, Sebastian Zug
autogenerated on Mon Oct 6 2014 10:13:55