depth_error_calibration.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import cv2
3 import numpy as np
4 import matplotlib
5 matplotlib.use('Agg') # NOQA
6 import matplotlib.pyplot as plt
7 import matplotlib.animation as animation
8 from jsk_recognition_msgs.msg import DepthErrorResult
9 from sklearn import linear_model
10 import time
11 import threading
12 import sys
13 import rospy
14 import argparse
15 import csv
16 import math
17 import datetime
18 from jsk_recognition_msgs.srv import SetDepthCalibrationParameter
19 from jsk_recognition_msgs.msg import DepthCalibrationParameter
20 from sensor_msgs.msg import Image
21 from cv_bridge import CvBridge, CvBridgeError
22 
23 xs = []
24 raw_xs = []
25 ys = []
26 us = []
27 vs = []
28 c_us = []
29 c_vs = []
30 value_cache = dict() # (u, v) -> [z]
31 eps_z = 0.1 # 10cm
32 lock = threading.Lock()
33 u_min = None
34 u_max = None
35 v_min = None
36 v_max = None
37 model = None
38 set_param = None
39 MODELS = ["linear", "quadratic", "quadratic-uv", "quadratic-uv-abs", "quadratic-uv-quadratic", "quadratic-uv-quadratic-abs"]
40 
41 # use raw_input for python2 c.f. https://stackoverflow.com/questions/5868506/backwards-compatible-input-calls-in-python
42 if hasattr(__builtins__, 'raw_input'):
43  input = raw_input
44 
45 def query_yes_no(question, default=None):
46  """Ask a yes/no question via raw_input() and return their answer.
47 
48  "question" is a string that is presented to the user.
49  "default" is the presumed answer if the user just hits <Enter>.
50  It must be "yes" (the default), "no" or None (meaning
51  an answer is required of the user).
52 
53  The "answer" return value is one of "yes" or "no".
54  """
55  valid = {"yes": True, "y": True, "ye": True,
56  "no": False, "n": False}
57  if default is None:
58  prompt = " [y/n] "
59  elif default == "yes":
60  prompt = " [Y/n] "
61  elif default == "no":
62  prompt = " [y/N] "
63  else:
64  raise ValueError("invalid default answer: '%s'" % default)
65 
66  while True:
67  sys.stdout.write(question + prompt)
68  choice = input().lower()
69  if default is not None and choice == '':
70  return valid[default]
71  elif choice in valid:
72  return valid[choice]
73  else:
74  sys.stdout.write("Please respond with 'yes' or 'no' "
75  "(or 'y' or 'n').\n")
76 
77 
79  if model == "linear":
80  return v[0]
81  elif model == "quadratic":
82  return v[1]
83  elif model == "quadratic-uv" or model == "quadratic-uv-abs":
84  return v[-3]
85  elif model == "quadratic-uv-quadratic" or model == "quadratic-uv-quadratic-abs":
86  return v[-5]
87 
88 def genFeatureVector(x, u, v, cu, cv):
89  global model
90  x2 = x * x
91  u2 = u * u
92  v2 = v * v
93  if model == "linear":
94  return [x]
95  elif model == "quadratic":
96  return [x2, x]
97  elif model == "quadratic-uv":
98  return [u * x2, v * x2, x2,
99  u * x, v * x, x,
100  u, v]
101  elif model == "quadratic-uv-abs":
102  u = abs(u - cu)
103  v = abs(v - cv)
104  return [u * x2, v * x2, x2,
105  u * x, v * x, x,
106  u, v]
107  elif model == "quadratic-uv-quadratic":
108  return [u2 * x2, u * x2, v2 * x2, v * x2, x2,
109  u2 * x, u * x, v2 * x, v * x, x,
110  u2, u, v2, v]
111  elif model == "quadratic-uv-quadratic-abs":
112  u = abs(u - cu)
113  v = abs(v - cv)
114  u2 = u * u
115  v2 = v * v
116  return [u2 * x2, u * x2, v2 * x2, v * x2, x2,
117  u2 * x, u * x, v2 * x, v * x, x,
118  u2, u, v2, v]
119 
120 def isValidClassifier(classifier):
121  # before classifire outputs meaningful value,
122  # intercept is a list, so we skip the value
123  c0 = classifier.intercept_
124  return not hasattr(c0, "__len__");
125 
126 def setParameter(classifier):
127  global set_param
128  c = classifier.coef_
129  c0 = classifier.intercept_
130  param = DepthCalibrationParameter()
131  if not isValidClassifier(classifier):
132  print("parameters are list")
133  return
134  if model == "linear":
135  param.coefficients2 = [0, 0, 0, 0, 0]
136  param.coefficients1 = [0, 0, 0, 0, c[0]]
137  param.coefficients0 = [0, 0, 0, 0, c0]
138  param.use_abs = False
139  elif model == "quadratic":
140  param.coefficients2 = [0, 0, 0, 0, c[0]]
141  param.coefficients1 = [0, 0, 0, 0, c[1]]
142  param.coefficients0 = [0, 0, 0, 0, c0]
143  param.use_abs = False
144  elif model == "quadratic-uv":
145  param.coefficients2 = [0, c[0], 0, c[1], c[2]]
146  param.coefficients1 = [0, c[3], 0, c[4], c[5]]
147  param.coefficients0 = [0, c[6], 0, c[7], c0]
148  param.use_abs = False
149  elif model == "quadratic-uv-abs":
150  param.coefficients2 = [0, c[0], 0, c[1], c[2]]
151  param.coefficients1 = [0, c[3], 0, c[4], c[5]]
152  param.coefficients0 = [0, c[6], 0, c[7], c0]
153  param.use_abs = True
154  elif model == "quadratic-uv-quadratic":
155  param.coefficients2 = c[0:5]
156  param.coefficients1 = c[5:10]
157  param.coefficients0 = [c[10], c[11], c[12], c[13], c0]
158  param.use_abs = False
159  elif model == "quadratic-uv-quadratic-abs":
160  param.coefficients2 = c[0:5]
161  param.coefficients1 = c[5:10]
162  param.coefficients0 = [c[10], c[11], c[12], c[13], c0]
163  param.use_abs = True
164  set_param(param)
165 
166 def processData(x, y, u, v, cu, cv, fit = True):
167  global xs, ys, classifier, u_min, u_max, v_min, v_max, raw_xs
168  uu = int(u/10)
169  vv = int(v/10)
170  with lock:
171  if (uu, vv) in value_cache:
172  zs = value_cache[(uu, vv)]
173  for z in zs:
174  if abs(z - y) < eps_z:
175  print("duplicated value")
176  return
177  else:
178  value_cache[(uu, vv)].append(y)
179  else:
180  value_cache[(uu, vv)] = [y]
181  raw_xs.append(x)
182  us.append(u)
183  vs.append(v)
184  c_us.append(cu)
185  c_vs.append(cv)
186  if u > u_min and u < u_max and v < v_max and v > v_min:
187  print((x, y))
188  xs.append(genFeatureVector(x, u, v, cu, cv))
189  ys.append(y)
190  if fit:
191  classifier.fit(xs, ys)
192  try:
193  setParameter(classifier)
194  except rospy.service.ServiceException as e:
195  rospy.logfatal("failed to call service: %s" % (e.message))
196  try:
197  print(modelEquationString(classifier))
198  except Exception as e:
199  rospy.logwarn("failed to print model: %s" % e.message)
200 
201  else:
202  print("(%d, %d) is out of range" % (u, v))
203 
204 def callback(msg):
205  global xs, ys, classifier, u_min, u_max, v_min, v_max, raw_xs
206 
207  x = msg.observed_depth
208  y = msg.true_depth
209  u = msg.u
210  v = msg.v
211  if math.isnan(x) or math.isnan(y):
212  return
213  processData(x, y, u, v, msg.center_u, msg.center_v)
214  updatePlot()
215 
216 def uvCoefString(c, absolute=False):
217  if absolute:
218  return "%f|u| + %f|v| + %f" % (c[0], c[1], c[2])
219  else:
220  return "%fu + %fv + %f" % (c[0], c[1], c[2])
221 def uvQuadraticCoefString(c, absolute=False):
222  if absolute:
223  return "%f|u|^2 + %f|u| + %f|v|^2 + %f|v| + %f" % (c[0], c[1], c[2], c[3], c[4])
224  else:
225  return "%fu^2 + %fu + %fv^2 + %fv + %f" % (c[0], c[1], c[2], c[3], c[4])
226 
227 def modelEquationString(classifier):
228  global model, xs, ys
229  c = classifier.coef_
230  i = classifier.intercept_
231  if model == "linear":
232  return "%fz + %f\n(score: %f)" % (
233  c[0], i,
234  classifier.score(xs, ys))
235  elif model == "quadratic":
236  return "%fz^2 + %fz + %f\n(score: %f)" % (
237  c[0],
238  c[1],
239  i,
240  classifier.score(xs, ys))
241  elif model == "quadratic-uv":
242  return "(%s)z^2 +\n(%s)z +\n%s\n(score: %f)" % (
243  uvCoefString(c[0:3]),
244  uvCoefString(c[3:6]),
245  uvCoefString([c[6], c[7], i]),
246  classifier.score(xs, ys))
247  elif model == "quadratic-uv-abs":
248  return "(%s)z^2 +\n(%s)z +\n%s\n(score: %f)" % (
249  uvCoefString(c[0:3], True),
250  uvCoefString(c[3:6], True),
251  uvCoefString([c[6], c[7], i], True),
252  classifier.score(xs, ys))
253  elif model == "quadratic-uv-quadratic":
254  return "(%s)z^2 +\n(%s)z +\n%s\n(score: %f)" % (
255  uvQuadraticCoefString(c[0:5]),
256  uvQuadraticCoefString(c[5:10]),
257  uvQuadraticCoefString([c[10], c[11], c[12], c[13], i]),
258  classifier.score(xs, ys))
259  elif model == "quadratic-uv-quadratic-abs":
260  return "(%s)z^2 +\n(%s)z +\n%s\n(score: %f)" % (
261  uvQuadraticCoefString(c[0:5], True),
262  uvQuadraticCoefString(c[5:10], True),
263  uvQuadraticCoefString([c[10], c[11], c[12], c[13], i], True),
264  classifier.score(xs, ys))
265 
266 def applyModel(x, u, v, cu, cv, clssifier):
267  global model
268  c = classifier.coef_
269  i = classifier.intercept_
270  if model == "linear":
271  return c[0] * x + i
272  elif model == "quadratic":
273  return c[0] * x * x + c[1] * x + i
274  elif model == "quadratic-uv":
275  return ((c[0] * u + c[1] * v + c[2]) * x * x +
276  (c[3] * u + c[4] * v + c[5]) * x +
277  c[6] * u + c[7] * v + i)
278  elif model == "quadratic-uv-abs":
279  u = abs(u - cu)
280  v = abs(v - cv)
281  return ((c[0] * u + c[1] * v + c[2]) * x * x +
282  (c[3] * u + c[4] * v + c[5]) * x +
283  c[6] * u + c[7] * v + i)
284  elif model == "quadratic-uv-quadratic":
285  u2 = u * u
286  v2 = v * v
287  return ((c[0] * u2 + c[1] * u + c[2] * v2 + c[3] * v + c[4]) * x * x +
288  (c[5] * u2 + c[6] * u + c[7] * v2 + c[8] * v + c[9]) * x +
289  (c[10] * u2 + c[11] * u + c[12] * v2 + c[13] * v + i))
290  elif model == "quadratic-uv-quadratic-abs":
291  u = abs(u - cu)
292  v = abs(v - cv)
293  u2 = u * u
294  v2 = v * v
295  return ((c[0] * u2 + c[1] * u + c[2] * v2 + c[3] * v + c[4]) * x * x +
296  (c[5] * u2 + c[6] * u + c[7] * v2 + c[8] * v + c[9]) * x +
297  (c[10] * u2 + c[11] * u + c[12] * v2 + c[13] * v + i))
298 
299 
301  global xs, ax, width, height
302  if rospy.is_shutdown():
303  plt.close()
304  return
305  with lock:
306  if len(xs) == 0:
307  return
308  try:
309  plt.cla()
310  plt.xlabel('Z from depth image')
311  plt.ylabel('Z from checker board')
312  plt.grid(True)
313  plt.title(model)
314  plt.scatter([getXFromFeatureVector(x) for x in xs[:-1]],
315  ys[:-1], s=10, c='b', zorder=10, alpha=0.1)
316  plt.scatter([getXFromFeatureVector(xs[-1])],
317  [ys[-1]], s=10, c='r', zorder=10, alpha=1.0)
318  xmin = np.amin([getXFromFeatureVector(x) for x in xs])
319  xmax = np.amax([getXFromFeatureVector(x) for x in xs])
320  X_test = [[xmin * xmin, xmin], [xmax * xmax, xmax]]
321  X_range = np.linspace(xmin, xmax, 100)
322  ax.plot(X_range, X_range, linewidth=2, color='green', alpha=0.5)
323  ax.plot(X_range,
324  applyModel(X_range,
325  width / 2, height / 2,
326  width / 2, height / 2,
327  classifier),
328  linewidth=2, color='red', alpha=0.5)
329  plt.text(xmin, xmax - 0.1,
330  modelEquationString(classifier),
331  fontsize=12)
332  # publish frequency image
333  bridge = CvBridge()
334  img = generateFrequencyMap()
335  pub_image.publish(bridge.cv2_to_imgmsg(img, "bgr8"))
336  # publish error plot
337  fig = plt.gcf()
338  fig.canvas.draw()
339  w, h = fig.canvas.get_width_height()
340  plot_img = np.fromstring(fig.canvas.tostring_rgb(), dtype=np.uint8)
341  fig.clf()
342  plot_img.shape = (h, w, 3)
343  plt.close()
344  pub_error_plot.publish(bridge.cv2_to_imgmsg(plot_img, "bgr8"))
345  except Exception as e:
346  rospy.logerr(e.message)
347 
349  global width, height
350  # bgr
351  img = np.tile(np.uint8([0,0,0]), (height // 10, width // 10, 1))
352  frequency = dict()
353  for (u, v) in value_cache.keys():
354  min_color = np.uint8([255, 0, 0])
355  max_color = np.uint8([0, 0, 255])
356  uu = u
357  vv = v
358  if (uu, vv) in frequency:
359  frequency[(uu, vv)] = frequency[(uu, vv)] + len(value_cache[(u, v)])
360  else:
361  frequency[(uu, vv)] = len(value_cache[(u, v)])
362  for (u, v) in frequency.keys():
363  r = min(frequency[(u, v)] / 10.0, 1)
364  img[v, u] = min_color * (1 - r) + max_color * r
365  return img
366 
367 def main():
368  global ax, xs, ys, classifier, u_min, u_max, v_min, v_max, model, set_param
369  global width, height, pub_image, pub_error_plot
370  pub_image = rospy.Publisher("~frequency_image", Image, queue_size=1)
371  pub_error_plot = rospy.Publisher("~error_plot_image", Image, queue_size=1)
372  set_param = rospy.ServiceProxy("/camera_remote/depth_calibration/set_calibration_parameter",
373  SetDepthCalibrationParameter)
374  # parse argument
375  parser = argparse.ArgumentParser()
376  parser.add_argument('--csv')
377  parser.add_argument('--model', default="linear")
378  parser.add_argument('--models', action="store_true", default=False)
379  parser.add_argument("--width", default=640)
380  parser.add_argument("--height", default=480)
381  args = parser.parse_args(rospy.myargv()[1:])
382  width = args.width
383  height = args.height
384  if args.models:
385  for m in MODELS:
386  print(m)
387  return
388  model = args.model
389  if model not in MODELS:
390  raise Exception("Unknown Model: %s" % (model))
391 
392  if not args.csv:
393  sub = rospy.Subscriber("depth_image_error/output",
394  DepthErrorResult, callback)
395  #plt.ion()
396  fig = plt.figure()
397  ax = plt.axes([.12, .12, .8, .8])
398  classifier = linear_model.LinearRegression()
399  u_min = rospy.get_param("~u_min", 0)
400  u_max = rospy.get_param("~u_max", 4096)
401  v_min = rospy.get_param("~v_min", 0)
402  v_max = rospy.get_param("~v_max", 4096)
403 
404  if args.csv:
405  for row in csv.reader(open(args.csv, "rb")):
406  x = float(row[0])
407  y = float(row[1])
408  u = float(row[2])
409  v = float(row[3])
410  cu = float(row[4])
411  cv = float(row[5])
412  processData(x, y, u, v, cu, cv, fit = False)
413  classifier.fit(xs, ys)
414  try:
415  setParameter(classifier)
416  except rospy.service.ServiceException as e:
417  rospy.logfatal("failed to call service: %s" % (e.message))
418  try:
419  plt.show()
420  finally:
421  if not args.csv:
422  csv_filename = "calibration-%s.csv" % datetime.datetime.now().strftime('%Y-%m-%d-%H-%M-%S')
423  print("Save calibration parameters to %s" % (csv_filename))
424  with open(csv_filename, "w") as f:
425  for x, y, u, v, cu, cv in zip(raw_xs, ys, us, vs, c_us, c_vs):
426  f.write("%f,%f,%d,%d,%f,%f\n" % (x, y, u, v, cu, cv))
427  dump = rospy.get_param("~dump_result_into_yaml", "query")
428  if dump is True or \
429  (dump == "query" and query_yes_no("Dump result into yaml file?")):
430  yaml_filename = "calibration_parameter_%s.yaml" % datetime.datetime.now().strftime('%Y_%m_%d_%H_%M_%S')
431  print("writing to %s" % yaml_filename)
432  c = classifier.coef_
433  if model == "quadratic-uv-abs" or model == "quadratic-uv-quadratic-abs":
434  use_abs = "True"
435  else:
436  use_abs = "False"
437 
438  with open(yaml_filename, "w") as f:
439  f.write("""
440 coefficients2: [%s, %s, %s, %s, %s]
441 coefficients1: [%s, %s, %s, %s, %s]
442 coefficients0: [%s, %s, %s, %s, %s]
443 use_abs: %s
444  """ % (
445  repr(c[0]), repr(c[1]), repr(c[2]), repr(c[3]), repr(c[4]),
446  repr(c[5]), repr(c[6]), repr(c[7]), repr(c[8]), repr(c[9]),
447  repr(c[10]), repr(c[11]), repr(c[12]), repr(c[13]), repr(classifier.intercept_),
448  use_abs))
449 
450 if __name__ == "__main__":
451  rospy.init_node("depth_error_logistic_regression")
452  main()
453  rospy.spin()
srv
depth_error_calibration.setParameter
def setParameter(classifier)
Definition: depth_error_calibration.py:126
depth_error_calibration.main
def main()
Definition: depth_error_calibration.py:367
msg
depth_error_calibration.updatePlot
def updatePlot()
Definition: depth_error_calibration.py:300
depth_error_calibration.modelEquationString
def modelEquationString(classifier)
Definition: depth_error_calibration.py:227
jsk_pcl_ros::min
double min(const OneDataStat &d)
wrapper function for min method for boost::function
Definition: one_data_stat.h:126
depth_error_calibration.isValidClassifier
def isValidClassifier(classifier)
Definition: depth_error_calibration.py:120
depth_error_calibration.applyModel
def applyModel(x, u, v, cu, cv, clssifier)
Definition: depth_error_calibration.py:266
depth_error_calibration.callback
def callback(msg)
Definition: depth_error_calibration.py:204
depth_error_calibration.uvCoefString
def uvCoefString(c, absolute=False)
Definition: depth_error_calibration.py:216
depth_error_calibration.generateFrequencyMap
def generateFrequencyMap()
Definition: depth_error_calibration.py:348
depth_error_calibration.uvQuadraticCoefString
def uvQuadraticCoefString(c, absolute=False)
Definition: depth_error_calibration.py:221
depth_error_calibration.query_yes_no
def query_yes_no(question, default=None)
Definition: depth_error_calibration.py:45
depth_error_calibration.processData
def processData(x, y, u, v, cu, cv, fit=True)
Definition: depth_error_calibration.py:166
depth_error_calibration.set_param
set_param
Definition: depth_error_calibration.py:38
depth_error_calibration.genFeatureVector
def genFeatureVector(x, u, v, cu, cv)
Definition: depth_error_calibration.py:88
depth_error_calibration.getXFromFeatureVector
def getXFromFeatureVector(v)
Definition: depth_error_calibration.py:78
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44