random_messages.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2008, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 #
33 
34 import rospy
35 import random
36 import genmsg.msgs
37 import genpy.dynamic
38 
39 def get_sub_defs(msg_fqn, msg_txt):
40  def_dict = {}
41  defs = msg_txt.split("\n" + "="*80 + "\n")
42  def_dict[msg_fqn] = defs[0]
43  for d in defs[1:]:
44  lines = d.splitlines()
45  if not lines[0].startswith("MSG: "):
46  raise Exception("Invalid sub definition!")
47  type = lines[0][5:].strip()
48  def_txt = "\n".join(lines[1:])
49  def_dict[type] = def_txt
50  return def_dict
51 
52 class RandomMsgGen(object):
53  def randstr(self, length=0):
54  if length == 0:
55  length = self.rand.randint(3,10)
56  return ''.join([chr(self.rand.randint(ord('a'), ord('z'))) for i in range(length)])
57 
58  def __init__(self, seed, num_topics, duration):
59  self.message_defs = {}
60  self.message_dict = {}
61  self.topic_dict = {}
62  self.duration = duration
63  self.output = []
64 
65  self.rand = random.Random(seed)
66 
67  for i in range(num_topics):
68  msg_pkg = self.randstr()
69  msg_name = self.randstr()
70  msg_fqn = "%s/%s"%(msg_pkg,msg_name)
71  msg_fields = []
72 
73  msg_def = ""
74  msg_sub_defs = {}
75 
76  for j in range(self.rand.randint(3,5)):
77  field_name = self.randstr()
78  field_type = self.rand.choice(genmsg.msgs.BUILTIN_TYPES + list(self.message_defs.keys()))
79  field_array = self.rand.choice(5*[""]+["[]","[%d]"%self.rand.randint(1,10)])
80 
81  if (field_type not in genmsg.msgs.BUILTIN_TYPES):
82  tmp = get_sub_defs(field_type, self.message_defs[field_type])
83  for (sm_type, sm_def) in tmp.items():
84  msg_sub_defs[sm_type] = sm_def
85 
86  msg_def = msg_def + "%s%s %s\n"%(field_type, field_array, field_name)
87 
88  for (t,d) in msg_sub_defs.items():
89  msg_def = msg_def + "\n" + "="*80 + "\n"
90  msg_def = msg_def + "MSG: %s\n"%(t)
91  msg_def = msg_def + d
92 
93  self.message_defs[msg_fqn] = msg_def
94 
95  topic_name = self.randstr()
96 
97  self.message_dict[msg_fqn] = genpy.dynamic.generate_dynamic(msg_fqn, msg_def)[msg_fqn]
98  self.topic_dict[topic_name] = self.message_dict[msg_fqn]
99 
100  time = 0.0
101  while time < duration:
102  topic = self.rand.choice(list(self.topic_dict.keys()))
103  msg_inst = self.rand_value(self.topic_dict[topic]._type)
104  self.output.append((topic, msg_inst, time))
105  time = time + self.rand.random()*.01
106 
107  def topics(self):
108  return self.topic_dict.items()
109 
110  def messages(self):
111  for m in self.output:
112  yield m
113 
114  def message_count(self):
115  return len(self.output)
116 
117  def rand_value(self, field_type):
118  if field_type == 'bool':
119  return self.rand.randint(0,1)
120  elif field_type == 'byte':
121  return self.rand.randint(0,2**7-1)
122  elif field_type == 'int8':
123  return self.rand.randint(-2**7,2**7-1)
124  elif field_type == 'int16':
125  return self.rand.randint(-2**15,2**15-1)
126  elif field_type == 'int32':
127  return self.rand.randint(-2**31,2**31-1)
128  elif field_type == 'int64':
129  return self.rand.randint(-2**63,2**63-1)
130  elif field_type == 'char':
131  return self.rand.randint(0,2**8-1)
132  elif field_type == 'uint8':
133  return self.rand.randint(0,2**8-1)
134  elif field_type == 'uint16':
135  return self.rand.randint(0,2**16-1)
136  elif field_type == 'uint32':
137  return self.rand.randint(0,2**32-1)
138  elif field_type == 'uint64':
139  return self.rand.randint(0,2**64-1)
140  elif field_type == 'float32':
141  return self.rand.random()
142  elif field_type == 'float64':
143  return self.rand.random()
144  elif field_type == 'string':
145  return self.randstr(100)
146  elif field_type == 'duration':
147  return rospy.Duration.from_sec(self.rand.random())
148  elif field_type == 'time':
149  return rospy.Time.from_sec(self.rand.random()*1000)
150  elif field_type.endswith(']'): # array type
151  base_type, is_array, array_len = genmsg.msgs.parse_type(field_type)
152 
153  if array_len is None:
154  array_len = self.rand.randint(1,100)
155 
156  # Make this more efficient rather than depend on recursion inside the array check
157  if field_type == 'bool':
158  return [ self.rand.randint(0,1) for i in range(0,array_len) ]
159  elif field_type == 'byte':
160  return [ self.rand.randint(-2**7,2**7-1) for i in range(0,array_len) ]
161  elif field_type == 'int8':
162  return [ self.rand.randint(-2**7,2**7-1) for i in range(0,array_len) ]
163  elif field_type == 'int16':
164  return [ self.rand.randint(-2**15,2**15-1) for i in range(0,array_len) ]
165  elif field_type == 'int32':
166  return [ self.rand.randint(-2**31,2**31-1) for i in range(0,array_len) ]
167  elif field_type == 'int64':
168  return [ self.rand.randint(-2**63,2**63-1) for i in range(0,array_len) ]
169  elif field_type == 'char':
170  return [ self.rand.randint(0,2**8-1) for i in range(0,array_len) ]
171  elif field_type == 'uint8':
172  return [ self.rand.randint(0,2**8-1) for i in range(0,array_len) ]
173  elif field_type == 'uint16':
174  return [ self.rand.randint(0,2**16-1) for i in range(0,array_len) ]
175  elif field_type == 'uint32':
176  return [ self.rand.randint(0,2**32-1) for i in range(0,array_len) ]
177  elif field_type == 'uint64':
178  return [ self.rand.randint(0,2**64-1) for i in range(0,array_len) ]
179  elif field_type == 'float32':
180  return [ self.rand.random() for i in range(0,array_len) ]
181  elif field_type == 'float64':
182  return [ self.rand.random() for i in range(0,array_len) ]
183  elif field_type == 'string':
184  return [ self.randstr(100) for i in range(0,array_len) ]
185  elif field_type == 'duration':
186  return [ rospy.Duration.from_sec(self.rand.random()) for i in range(0,array_len) ]
187  elif field_type == 'time':
188  return [ rospy.Time.from_sec(self.rand.random()*1000) for i in range(0,array_len) ]
189  else:
190  return [ self.rand_value(base_type) for i in range(0,array_len) ]
191 
192  else:
193  msg_class = self.message_dict[field_type]
194  msg_inst = msg_class()
195  for s in msg_inst.__slots__:
196  ind = msg_inst.__slots__.index(s)
197  msg_inst.__setattr__(s,self.rand_value(msg_inst._slot_types[ind]))
198  return msg_inst
def __init__(self, seed, num_topics, duration)
def get_sub_defs(msg_fqn, msg_txt)
def rand_value(self, field_type)
def randstr(self, length=0)


test_rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:53:09