haptix_run.py
Go to the documentation of this file.
1 from timeout import timeout
2 import rospy
3 import matplotlib.pyplot as plt
4 rospy.init_node('tester')
5 
6 
7 
8 # def f(t):
9 # # @timeout(t)
10 # def h():
11 # rospy.sleep(20)
12 # h()
13 
14 # f(1)
15 
16 def plot_dual(config):
17  plt.clf()
18  data_sim = config['/simulation/joint_states/position']
19  data_real = config['/real/joint_states/position']
20  plot(data_sim)
21  plot(data_real)
22  plt.draw()
23  plt.show()
24 
25 
26 def plot(data, style = '-'):
27 
28  print "single plot %d" % data.shape[1]
29 
30  plt.ion()
31 
32  for i in range(data.shape[1]):
33  col = data[:, i]
34  plt.subplot(3, 2, i+1)
35  # print "plottting data %d" % i
36  # print col
37 
38  plt.plot(col, ls = style)#, hold=True)
39  # plt.ylabel(key)
40  plt.xlabel('time')
41 
42  plt.pause(0.05)
43 
44 def error(x, y, axis = 0):
45  mserr = ((x - y) ** 2).mean(axis=axis)
46  print "################# individual errors ###################"
47  print(mserr)
48  mserr = sum(mserr)
49  return mserr
50 
51 
52 def shift(x, y, i):
53  if i>=0:
54  x_new = x[i:]
55  y_new = y[:len(y)-i]
56  else:
57  x_new = x[0:len(x)+i]
58  y_new = y[-i:]
59  return x_new, y_new
60 
61 
62 def find_best_error(x, y, offset, axis = 0):
63  min_err = float("inf")
64  min_index = 0
65  for i in range(-offset, offset+1):
66  x_new, y_new = shift(x, y, i)
67  # print "################"
68  # print len(x_new)
69  # print len(y_new)
70 
71  err = error(x_new, y_new, axis)
72  print err, i
73  if err < min_err:
74  min_err = err
75  min_index = i
76 
77  print min_err, min_index
78 
79  return min_err, min_index
80 
81 
82 def f(config, axis = 0):
83 
84  print "the config is:"
85  print(config)
86  sim_pos = config['/simulation/joint_states/position']
87  # sim_pos[:,[2,1,0,3,4,5]] = sim_pos[:,[0,1,2,3,4,5]]
88 
89 
90  real_pos = config['/real/joint_states/position']
91 
92  sim_pos = sim_pos[:,[1,3,4,5,6,8]]
93  real_pos = real_pos[:,[1,3,4,5,6,8]]
94 
95  mserr, offset = find_best_error(sim_pos, real_pos, len(sim_pos)/4)
96 
97  sim_pos, real_pos = shift(sim_pos, real_pos, offset)
98 
99  config['/simulation/joint_states/position'] = sim_pos
100  config['/real/joint_states/position'] = real_pos
101 
102  print "before plot"
103 
104  # plot(sim_pos)
105  # plot(real_pos)
106  # plt.draw()
107  # plt.show()
108 
109 
110  plot_dual(config)
111 
112  print "after plot"
113 
114  # rospy.sleep(50)
115 
116  # mserr = ((sim_pos - real_pos) ** 2).mean(axis=axis)
117  # mserr = sum(mserr)
118  print(mserr)
119  return mserr
120 
121 
122 from dynamic_tuner import *
123 params = rospy.get_param("/optimizable_params")
124 values = rospy.get_param("/objective_values")
125 
126 print "###"
127 print params
128 
129 print params, values
130 
131 src_topic = '/haptix_deka_controller/command'
132 dst_topic = '/haptix_deka_controller/command'
133 
134 # src_bag = 'exp-1.bag'
135 src_bag = 'exp-rand-01.bag'
136 dst_bag = 'test_sim.bag'
137 
138 # start = {'/haptix_deka_controller/follow_joint_trajectory/status/status_list[0]/status':1, '/haptix_deka_controller/follow_joint_trajectory/feedback/status/status':1}
139 # end = {'/haptix_deka_controller/follow_joint_trajectory/result':None, '/haptix_deka_controller/follow_joint_trajectory/result':None}
140 
141 start = {}
142 end = {}
143 
144 print "ready to start"
145 
146 dyn = dynamic_tuner(params, values, src_bag, dst_bag, src_topic, dst_topic, objective = f, start_signal = start, end_signal = end)
147 
148 
149 print "starting..."
150 dyn.tune_params()
151 
152 
153 # bag = start_simulation(src_bag, dst_bag, src_topic, dst_topic)
154 
155 """
156 from dynamic_tuner import *
157 start_simulation('exp-real-7.bag', 'test_sim.bag', '/follow_joint_trajectory/goal', '/arm_controller/follow_joint_trajectory/goal', {'/follow_joint_trajectory/goal':None, '/arm_controller/follow_joint_trajectory/goal':None}, {'/arm_controller/follow_joint_trajectory/result':None, '/follow_joint_trajectory/result':None})
158 
159 
160 from dynamic_tuner import *
161 start_simulation('exp-real-7.bag', 'test_sim.bag', '/follow_joint_trajectory/goal', '/arm_controller/follow_joint_trajectory/goal', {'/follow_joint_trajectory/status/status_list[0]/status':1, '/arm_controller/follow_joint_trajectory/feedback/status/status':1}, {'/arm_controller/follow_joint_trajectory/result':None, '/follow_joint_trajectory/result':None})
162 
163 
164 
165 sim_bag = rosbag.Bag('test_sim.bag', 'r')
166 bag = restamp(sim_bag, output_bag_file = 'sim-restamped.bag', prefix = SIM_PREFIX, start_signal = start_signal, end_signal = end_signal)
167 
168 
169 dyn._optimizer.optimize()
170 
171 dyn._optimizer.set_params_config({'/arm_controller/gains/elbow_joint/p':100001})
172 desc = dyn.get_params_desc(['/arm_controller/gains/elbow_joint/p', '/arm_controller/gains/elbow_joint/i', '/arm_controller/gains/wrist_3_joint/d'])
173 """
def plot_dual(config)
Definition: haptix_run.py:16
def shift(x, y, i)
Definition: haptix_run.py:52
def plot(data, style='-')
Definition: haptix_run.py:26
def f(config, axis=0)
Definition: haptix_run.py:82
def find_best_error(x, y, offset, axis=0)
Definition: haptix_run.py:62
def error(x, y, axis=0)
Definition: haptix_run.py:44
def restamp(bag, output_bag_file='restamped.bag', values=[], prefix="", start_signal={}, end_signal={})


dyn_tune
Author(s):
autogenerated on Mon Jun 10 2019 13:03:17