Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 import rospy
00020 import os
00021 import yaml
00022 import rospkg
00023
00024 try:
00025 from yaml import CLoader as Loader, CDumper as Dumper
00026 except ImportError:
00027 from yaml import Loader, Dumper
00028
00029
00030 class PidLoader(object):
00031
00032 """
00033 Loads pid parameters of each controller in parameters_dict from a yaml file
00034 """
00035
00036 def __init__(self):
00037 pass
00038
00039 def get_settings(self, param_name):
00040 param_dict = {}
00041 if len(param_name) == 2:
00042 try:
00043 tmp_dict = rospy.get_param(param_name[0])
00044 except KeyError:
00045 return -1
00046 for item in tmp_dict.items():
00047 param_dict["pos/" + item[0]] = item[1]
00048
00049 try:
00050 tmp_dict = rospy.get_param(param_name[1])
00051 except KeyError:
00052 return -1
00053 for item in tmp_dict.items():
00054 param_dict["vel/" + item[0]] = item[1]
00055 else:
00056 try:
00057 param_dict = rospy.get_param(param_name)
00058 except KeyError:
00059 return -1
00060 return param_dict
00061
00062
00063 class PidSaver(object):
00064
00065 """
00066 Saves pid parameters of each controller in parameters_dict in a yaml file
00067 """
00068
00069 def __init__(self, file_path):
00070 self.path = file_path
00071
00072 def save_settings(self, param_path, parameters_dict):
00073 f = open(self.path, 'r')
00074 document = ""
00075 for line in f.readlines():
00076 document += line
00077 f.close()
00078
00079 yaml_config = yaml.load(document)
00080
00081 for item in parameters_dict.items():
00082 if "pos/" in item[0]:
00083 yaml_config[param_path[0]]["position_pid"][
00084 item[0].split("pos/")[1]] = item[1]
00085 elif "vel/" in item[0]:
00086 yaml_config[param_path[0]]["velocity_pid"][
00087 item[0].split("vel/")[1]] = item[1]
00088 else:
00089 yaml_config[param_path[0]][param_path[1]][item[0]] = item[1]
00090
00091 full_config_to_write = yaml.dump(yaml_config, default_flow_style=False)
00092
00093 f = open(self.path, 'w')
00094 f.write(full_config_to_write)
00095 f.close()
00096
00097 if __name__ == '__main__':
00098 path_to_config = "~"
00099 try:
00100 path_to_config = os.path.join(
00101 rospkg.RosPack().get_path("sr_edc_controller_configuration"))
00102
00103 pid_saver = PidSaver(
00104 path_to_config + "/sr_edc_mixed_position_velocity_joint_controllers.yaml")
00105 pid_saver.save_settings(
00106 ["sh_wrj2_mixed_position_velocity_controller", "pid"], {"d": 1.0})
00107 except:
00108 rospy.logwarn(
00109 "couldnt find the sr_edc_controller_configuration package")