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