def __init__(self, **kwargs): self.black_box_db_name = kwargs.get('db_name', 'logs') self.sync_time = kwargs.get('sync_time', True) self.time_step = kwargs.get('time_step', 1.0) self.sleep_duration = kwargs.get('sleep_duration', 0.5) actual_start_time = DBUtils.get_db_oldest_timestamp( self.black_box_db_name) actual_stop_time = DBUtils.get_db_newest_timestamp( self.black_box_db_name) self.start_timestamp = kwargs.get('start_time', actual_start_time) self.stop_timestamp = kwargs.get('stop_time', actual_stop_time) if actual_start_time > self.start_timestamp or \ actual_stop_time < self.stop_timestamp or \ self.start_timestamp > self.stop_timestamp : print( "WARNING: Incorrect start or stop time. Using default duration" ) self.start_timestamp = actual_start_time self.stop_timestamp = actual_stop_time self.current_time = self.start_timestamp self.status = "PAUSED" self.topic_managers = [] self.topic_manager_threads = [] data_collections = DBUtils.get_data_collection_names( self.black_box_db_name) # create list of locks for syncing (each for one topic) self.locks = [ multiprocessing.Lock() for collection in data_collections ] # create list of queues to access global current time (maintained by syncronizer) self.queues = [ multiprocessing.Queue() for collection in data_collections ] self.queues.append( multiprocessing.Queue()) # for current(parent) process sync_pause_conn, self.rosbag_pause_conn = multiprocessing.Pipe( duplex=True) # create syncronizer object and assign it to a thread self.sync = Syncronizer(self.start_timestamp, self.locks, self.queues, sync_pause_conn, time_step=self.time_step, sleep_duration=self.sleep_duration) self.sync_thread = multiprocessing.Process( target=self.sync.increment_time, daemon=True) # create topic_utils object and assign it to a thread for each topic for i, collection in enumerate(data_collections): collection_metadata = DBUtils.get_collection_metadata( self.black_box_db_name, collection) topic_manager = TopicUtils( collection_metadata['ros']['topic_name'], collection_metadata['ros']['msg_type'], collection_metadata['ros']['direct_msg_mapping']) self.topic_managers.append(topic_manager) data_cursor = DBUtils.get_doc_cursor(self.black_box_db_name, collection, self.start_timestamp, self.stop_timestamp) data_thread = multiprocessing.Process( target=topic_manager.publish_data, kwargs={ 'dict_msgs': data_cursor, 'sync_time': self.sync_time, 'global_clock_start': self.start_timestamp, 'lock': self.locks[i], 'queue': self.queues[i] }, daemon=True) # data_thread.daemon = True self.topic_manager_threads.append(data_thread) for data_thread in self.topic_manager_threads: data_thread.start() self.sync_thread.start()
stdscr.refresh() if __name__ == '__main__': # rospy.init_node('rosbag_play') config_param = get_config_param() run_events = False parser = argparse.ArgumentParser(description="Play rosbag from mongo db") parser.add_argument('-db', help='name of the mongo db', default=config_param['db_name']) parser.add_argument('-e', '--events', action='store_true', help='Enable events playback') args = parser.parse_args() db_name = args.db if args.events and 'ros_ropod_event' in DBUtils.get_data_collection_names(db_name) \ and len(DBUtils.get_all_docs(db_name, 'ros_ropod_event')) > 0: events = DBUtils.get_all_docs(db_name, 'ros_ropod_event') chosen_event_index = choose_event(events, 1) while chosen_event_index != 0 : chosen_event = events[chosen_event_index-1] event_time = chosen_event['timestamp'] play_rosbag(event_time-config_param['event_playback_duration'], event_time+config_param['event_playback_duration']) chosen_event_index = choose_event(events, chosen_event_index) else : start_time = DBUtils.get_db_oldest_timestamp(db_name) stop_time = DBUtils.get_db_newest_timestamp(db_name) start_time, stop_time = get_desired_duration(start_time, stop_time) play_rosbag(start_time, stop_time)
def test_get_db_newest_timestamp(self): timestamp = DBUtils.get_db_newest_timestamp(db_name=self.test_db_name) self.assertEqual(timestamp, 1544441433.7863772)
sys.exit(1) bb_config_file = sys.argv[1] config_params = ConfigFileReader.load_config(bb_config_file) db_name = config_params.default.db_name db_port = 27017 pyre_comm = TestPyreCommunicator(['ROPOD'], 'black_box_001') test_start_time = time.time() test_duration = 5 print("Testing ... (for", test_duration, "seconds)") try: # First test case print("\n" * 3, "Test 1", "\n" * 3) pyre_comm.send_request("BLACK-BOX_LOGGING_CMD", {'cmd': "STOP"}) while test_start_time + test_duration > time.time(): newest_timestamp = DBUtils.get_db_newest_timestamp(db_name) if newest_timestamp < time.time(): print("Stop test successfull") time.sleep(0.2) # Second test case print("\n" * 3, "Test 2", "\n" * 3) pyre_comm.send_request("BLACK-BOX_LOGGING_CMD", {'cmd': "START"}) test_start_time = time.time() while test_start_time + test_duration > time.time(): newest_timestamp = DBUtils.get_db_newest_timestamp(db_name) if newest_timestamp > test_start_time: print("Start test successfull") time.sleep(0.2) # Third test case