00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 import roslib
00034 roslib.load_manifest('test_rosbag')
00035
00036 import rospy
00037 import random
00038 import roslib.msgs
00039 import roslib.genpy
00040
00041 def get_sub_defs(msg_fqn, msg_txt):
00042 def_dict = {}
00043 defs = msg_txt.split("\n" + "="*80 + "\n")
00044 def_dict[msg_fqn] = defs[0]
00045 for d in defs[1:]:
00046 lines = d.splitlines()
00047 if not lines[0].startswith("MSG: "):
00048 raise Exception("Invalid sub definition!")
00049 type = lines[0][5:].strip()
00050 def_txt = "\n".join(lines[1:])
00051 def_dict[type] = def_txt
00052 return def_dict
00053
00054 class RandomMsgGen(object):
00055 def randstr(self, length=0):
00056 if length == 0:
00057 length = self.rand.randint(3,10)
00058 return ''.join([chr(self.rand.randint(ord('a'), ord('z'))) for i in xrange(length)])
00059
00060 def __init__(self, seed, num_topics, duration):
00061 self.message_defs = {}
00062 self.message_dict = {}
00063 self.topic_dict = {}
00064 self.duration = duration
00065 self.output = []
00066
00067 self.rand = random.Random(seed)
00068
00069 for i in xrange(num_topics):
00070 msg_pkg = self.randstr()
00071 msg_name = self.randstr()
00072 msg_fqn = "%s/%s"%(msg_pkg,msg_name)
00073 msg_fields = []
00074
00075 msg_def = ""
00076 msg_sub_defs = {}
00077
00078 for j in xrange(self.rand.randint(3,5)):
00079 field_name = self.randstr()
00080 field_type = self.rand.choice(roslib.msgs.BUILTIN_TYPES + self.message_defs.keys())
00081 field_array = self.rand.choice(5*[""]+["[]","[%d]"%self.rand.randint(1,10)])
00082
00083 if (field_type not in roslib.msgs.BUILTIN_TYPES):
00084 tmp = get_sub_defs(field_type, self.message_defs[field_type])
00085 for (sm_type, sm_def) in tmp.iteritems():
00086 msg_sub_defs[sm_type] = sm_def
00087
00088 msg_def = msg_def + "%s%s %s\n"%(field_type, field_array, field_name)
00089
00090 for (t,d) in msg_sub_defs.iteritems():
00091 msg_def = msg_def + "\n" + "="*80 + "\n"
00092 msg_def = msg_def + "MSG: %s\n"%(t)
00093 msg_def = msg_def + d
00094
00095 self.message_defs[msg_fqn] = msg_def
00096
00097 topic_name = self.randstr()
00098
00099 self.message_dict[msg_fqn] = roslib.genpy.generate_dynamic(msg_fqn, msg_def)[msg_fqn]
00100 self.topic_dict[topic_name] = self.message_dict[msg_fqn]
00101
00102 time = 0.0
00103 while time < duration:
00104 topic = self.rand.choice(self.topic_dict.keys())
00105 msg_inst = self.rand_value(self.topic_dict[topic]._type)
00106 self.output.append((topic, msg_inst, time))
00107 time = time + self.rand.random()*.01
00108
00109 def topics(self):
00110 return self.topic_dict.iteritems()
00111
00112 def messages(self):
00113 for m in self.output:
00114 yield m
00115
00116 def message_count(self):
00117 return len(self.output)
00118
00119 def rand_value(self, field_type):
00120 if field_type == 'bool':
00121 return self.rand.randint(0,1)
00122 elif field_type == 'byte':
00123 return self.rand.randint(0,2**7-1)
00124 elif field_type == 'int8':
00125 return self.rand.randint(-2**7,2**7-1)
00126 elif field_type == 'int16':
00127 return self.rand.randint(-2**15,2**15-1)
00128 elif field_type == 'int32':
00129 return self.rand.randint(-2**31,2**31-1)
00130 elif field_type == 'int64':
00131 return self.rand.randint(-2**63,2**63-1)
00132 elif field_type == 'char':
00133 return self.rand.randint(0,2**8-1)
00134 elif field_type == 'uint8':
00135 return self.rand.randint(0,2**8-1)
00136 elif field_type == 'uint16':
00137 return self.rand.randint(0,2**16-1)
00138 elif field_type == 'uint32':
00139 return self.rand.randint(0,2**32-1)
00140 elif field_type == 'uint64':
00141 return self.rand.randint(0,2**64-1)
00142 elif field_type == 'float32':
00143 return self.rand.random()
00144 elif field_type == 'float64':
00145 return self.rand.random()
00146 elif field_type == 'string':
00147 return self.randstr(100)
00148 elif field_type == 'duration':
00149 return rospy.Duration.from_sec(self.rand.random())
00150 elif field_type == 'time':
00151 return rospy.Time.from_sec(self.rand.random()*1000)
00152 elif field_type.endswith(']'):
00153 base_type, is_array, array_len = roslib.msgs.parse_type(field_type)
00154
00155 if array_len is None:
00156 array_len = self.rand.randint(1,100)
00157
00158
00159 if field_type == 'bool':
00160 return [ self.rand.randint(0,1) for i in xrange(0,array_len) ]
00161 elif field_type == 'byte':
00162 return [ self.rand.randint(-2**7,2**7-1) for i in xrange(0,array_len) ]
00163 elif field_type == 'int8':
00164 return [ self.rand.randint(-2**7,2**7-1) for i in xrange(0,array_len) ]
00165 elif field_type == 'int16':
00166 return [ self.rand.randint(-2**15,2**15-1) for i in xrange(0,array_len) ]
00167 elif field_type == 'int32':
00168 return [ self.rand.randint(-2**31,2**31-1) for i in xrange(0,array_len) ]
00169 elif field_type == 'int64':
00170 return [ self.rand.randint(-2**63,2**63-1) for i in xrange(0,array_len) ]
00171 elif field_type == 'char':
00172 return [ self.rand.randint(0,2**8-1) for i in xrange(0,array_len) ]
00173 elif field_type == 'uint8':
00174 return [ self.rand.randint(0,2**8-1) for i in xrange(0,array_len) ]
00175 elif field_type == 'uint16':
00176 return [ self.rand.randint(0,2**16-1) for i in xrange(0,array_len) ]
00177 elif field_type == 'uint32':
00178 return [ self.rand.randint(0,2**32-1) for i in xrange(0,array_len) ]
00179 elif field_type == 'uint64':
00180 return [ self.rand.randint(0,2**64-1) for i in xrange(0,array_len) ]
00181 elif field_type == 'float32':
00182 return [ self.rand.random() for i in xrange(0,array_len) ]
00183 elif field_type == 'float64':
00184 return [ self.rand.random() for i in xrange(0,array_len) ]
00185 elif field_type == 'string':
00186 return [ self.randstr(100) for i in xrange(0,array_len) ]
00187 elif field_type == 'duration':
00188 return [ rospy.Duration.from_sec(self.rand.random()) for i in xrange(0,array_len) ]
00189 elif field_type == 'time':
00190 return [ rospy.Time.from_sec(self.rand.random()*1000) for i in xrange(0,array_len) ]
00191 else:
00192 return [ self.rand_value(base_type) for i in xrange(0,array_len) ]
00193
00194 else:
00195 msg_class = self.message_dict[field_type]
00196 msg_inst = msg_class()
00197 for s in msg_inst.__slots__:
00198 ind = msg_inst.__slots__.index(s)
00199 msg_inst.__setattr__(s,self.rand_value(msg_inst._slot_types[ind]))
00200 return msg_inst