def OnInit(self): try: if self.options.record: # Connect to ROS master if not self.connect_to_ros(): raise Exception('recording requires connection to master') # Get filename to record to record_filename = time.strftime('%Y-%m-%d-%H-%M-%S.bag', time.localtime(time.time())) if self.options.name: record_filename = self.options.name if not record_filename.endswith('.bag'): record_filename += '.bag' elif self.options.prefix: prefix = self.options.prefix if prefix.endswith('.bag'): prefix = prefix[:-len('.bag')] if prefix: record_filename = '%s_%s' % (prefix, record_filename) rospy.loginfo('Recording to %s.' % record_filename) # Create main timeline frame self.frame = BaseFrame(None, 'rxbag', 'Timeline') self.frame.BackgroundColour = wx.WHITE self.frame.Bind(wx.EVT_CLOSE, lambda e: wx.Exit()) scroll = wx.ScrolledWindow(self.frame, -1) scroll.BackgroundColour = wx.WHITE timeline = Timeline(scroll, -1) timeline.Size = (100, 100) self.frame.Show() self.SetTopWindow(self.frame) timeline.SetFocus() if self.options.record: timeline.record_bag(record_filename, all=self.options.all, topics=self.args, regex=self.options.regex, limit=self.options.limit) else: RxBagInitThread(self, timeline) except Exception, ex: print >> sys.stderr, 'Error initializing application:', ex #import traceback #traceback.print_exc() return False