def init(contr): """ General initialization of MORSE Here, all components, modifiers and middlewares are initialized. """ init_logging() logger.log(SECTION, 'PRE-INITIALIZATION') # Get the version of Python used # This is used to determine also the version of Blender persistantstorage.pythonVersion = sys.version_info logger.info("Python Version: %s.%s.%s" % persistantstorage.pythonVersion[:3]) logger.info("Blender Version: %s.%s.%s" % morse.core.blenderapi.version()) logger.info("Python path: %s" % sys.path) logger.info("PID: %d" % os.getpid()) persistantstorage.morse_initialised = False persistantstorage.time = TimeStrategies.make(morse.core.blenderapi.getssr()['time_management'], morse.core.blenderapi.getssr().get('use_relative_time', False)) # Variable to keep trac of the camera being used persistantstorage.current_camera_index = 0 init_ok = True init_ok = init_ok and create_dictionaries() persistantstorage.internal_syncer = None logger.log(SECTION, 'SUPERVISION SERVICES INITIALIZATION') init_ok = init_ok and init_supervision_services() # Make sure to start the internal syncer after initialization of # time_scale (done in in init_supervision_services) try: use_ = morse.core.blenderapi.getssr()['use_internal_syncer'] if use_: persistantstorage.internal_syncer = MorseSyncProcess() except KeyError: pass logger.log(SECTION, 'SCENE INITIALIZATION') if MULTINODE_SUPPORT: init_multinode() init_ok = init_ok and link_services() init_ok = init_ok and add_modifiers() init_ok = init_ok and link_datastreams() init_ok = init_ok and load_overlays() if init_ok: check_dictionaries() persistantstorage.morse_initialised = True logger.log(ENDSECTION, 'SCENE INITIALIZED') else: logger.critical('INITIALIZATION FAILED!') logger.info("Exiting now.") contr = morse.core.blenderapi.controller() close_all(contr) quit(contr)
def setUp(self): testlogger.info("Starting test " + self.id() + " in " + TimeStrategies.human_repr(CURRENT_TIME_MODE)) self.logfile_name = self.__class__.__name__ + ".log" # Wait for a second # to wait for ports open in previous tests to be closed sleep(1) self.morse_initialized = False self.setUpMw() self.startmorse(self) self.t = threading.Thread(target=self._checkMorseException) self.t.start()
def init(contr): """ General initialization of MORSE Here, all components, modifiers and middlewares are initialized. """ init_logging() logger.log(SECTION, "PRE-INITIALIZATION") # Get the version of Python used # This is used to determine also the version of Blender persistantstorage.pythonVersion = sys.version_info logger.info("Python Version: %s.%s.%s" % persistantstorage.pythonVersion[:3]) logger.info("Blender Version: %s.%s.%s" % morse.core.blenderapi.version()) logger.info("Python path: %s" % sys.path) logger.info("PID: %d" % os.getpid()) persistantstorage.morse_initialised = False persistantstorage.time = TimeStrategies.make(morse.core.blenderapi.getssr()["time_management"]) # Variable to keep trac of the camera being used persistantstorage.current_camera_index = 0 init_ok = True init_ok = init_ok and create_dictionaries() logger.log(SECTION, "SUPERVISION SERVICES INITIALIZATION") init_ok = init_ok and init_supervision_services() logger.log(SECTION, "SCENE INITIALIZATION") if MULTINODE_SUPPORT: init_multinode() init_ok = init_ok and link_services() init_ok = init_ok and add_modifiers() init_ok = init_ok and link_datastreams() init_ok = init_ok and load_overlays() if init_ok: check_dictionaries() persistantstorage.morse_initialised = True logger.log(ENDSECTION, "SCENE INITIALIZED") else: logger.critical("INITIALIZATION FAILED!") logger.info("Exiting now.") contr = morse.core.blenderapi.controller() close_all(contr) quit(contr)
def generate_builder_script(self, test_case): tmp_name = "" # We need to generate a temp builder file in case of running # several test cases with different environment: # Blender must be restarted and called again with the right # environment. with tempfile.NamedTemporaryFile(delete = False) as tmp: tmp.write(b"from morse.builder import *\n") tmp.write(b"from morse.builder.actuators import *\n") tmp.write(b"from morse.builder.sensors import *\n") tmp.write(b"from morse.builder.blenderobjects import *\n") tmp.write(b"class MyEnv():\n") tmp.write(inspect.getsource(test_case.setUpEnv).encode()) tmp.write(b" env.set_time_strategy(") tmp.write(TimeStrategies.python_repr(CURRENT_TIME_MODE)) tmp.write(b")\n") tmp.write(b"MyEnv().setUpEnv()\n") tmp.flush() tmp_name = tmp.name testlogger.info("Created a temporary builder file for test-case " +\ test_case.__class__.__name__) return tmp_name