diff --git a/concert_service_manager/src/concert_service_manager/load_params.py b/concert_service_manager/src/concert_service_manager/load_params.py index ca794cc..8278666 100644 --- a/concert_service_manager/src/concert_service_manager/load_params.py +++ b/concert_service_manager/src/concert_service_manager/load_params.py @@ -16,27 +16,12 @@ # Methods ############################################################################## +def load_parameters_from_resource(parameter_resource_name, namespace, name, load): + filepath = rocon_python_utils.ros.find_resource_from_string(resource_name, extension='parameters') + load_parameters_from_file(filepath, namespace, name, load) -def load_parameters_from_file(parameter_file, namespace, name, load): - filepath = rocon_python_utils.ros.find_resource_from_string(parameter_file, extension='parameters') - - with open(filepath) as f: - params = yaml.load(f) - for k, v in params.items(): - if k in INVALID_PARAM: - if load: - rospy.logwarn("Service Manager : %s%s [%s]" % (str(k), ' is prohibitted parameter. Ignoring...', name)) - continue - param_name = namespace + '/' + k - if load: - rospy.set_param(param_name, v) - else: - rospy.delete_param(param_name) - - -def load_parameters_from_cache(catche_file_path, namespace, name, load): - filepath = catche_file_path - +def load_parameters_from_file(parameter_file_path, namespace, name, load): + filepath = parameter_file_path with open(filepath) as f: params = yaml.load(f) for k, v in params.items(): @@ -48,4 +33,4 @@ def load_parameters_from_cache(catche_file_path, namespace, name, load): if load: rospy.set_param(param_name, v) else: - rospy.delete_param(param_name) + rospy.delete_param(param_name) \ No newline at end of file diff --git a/concert_service_manager/src/concert_service_manager/service_instance.py b/concert_service_manager/src/concert_service_manager/service_instance.py index 6e6b6c9..cdd53fb 100644 --- a/concert_service_manager/src/concert_service_manager/service_instance.py +++ b/concert_service_manager/src/concert_service_manager/service_instance.py @@ -19,7 +19,7 @@ import rocon_interactions import unique_id -from .load_params import load_parameters_from_cache +from .load_params import load_parameters_from_file from .utils import * ############################################################################## @@ -87,9 +87,8 @@ def enable(self, unique_identifier, interactions_loader): # load up parameters first so that when start runs, it can find the params immediately if self.msg.parameters != '': namespace = concert_msgs.Strings.SERVICE_NAMESPACE + '/' + self.msg.name - #load_parameters_from_file(self.msg.parameters, namespace, self.msg.name, load=True) parameter_path = os.path.join(get_service_profile_cache_home(self._concert_name, self.name), self.name + '.parameters') - load_parameters_from_cache(parameter_path, namespace, self.msg.name, load=True) + load_parameters_from_file(parameter_path, namespace, self.msg.name, load=True) # Refresh the unique id self.msg.uuid = unique_id.toMsg(unique_identifier) self._start() @@ -124,9 +123,8 @@ def disable(self, interactions_loader): interactions_loader.load(interaction_path, namespace=self._namespace, load=False, is_relative_path=False) if self.msg.parameters != '': namespace = concert_msgs.Strings.SERVICE_NAMESPACE + '/' + self.msg.name - #load_parameters_from_file(self.msg.parameters, namespace, self.msg.name, load=False) parameter_path = os.path.join(get_service_profile_cache_home(self._concert_name, self.name), self.name + '.parameters') - load_parameters_from_cache(parameter_path, namespace, self.msg.name, load=False) + load_parameters_from_file(parameter_path, namespace, self.msg.name, load=False) launcher_type = self.msg.launcher_type force_kill = False