6 import matplotlib.pyplot 
as plt
 
    7 import matplotlib.animation 
as animation
 
    9 from sklearn 
import linear_model
 
   20 from sensor_msgs.msg 
import Image
 
   21 from cv_bridge 
import CvBridge, CvBridgeError
 
   32 lock = threading.Lock()
 
   39 MODELS = [
"linear", 
"quadratic", 
"quadratic-uv", 
"quadratic-uv-abs", 
"quadratic-uv-quadratic", 
"quadratic-uv-quadratic-abs"]
 
   42 if hasattr(__builtins__, 
'raw_input'):
 
   46     """Ask a yes/no question via raw_input() and return their answer. 
   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). 
   53     The "answer" return value is one of "yes" or "no". 
   55     valid = {
"yes": 
True, 
"y": 
True, 
"ye": 
True,
 
   56              "no": 
False, 
"n": 
False}
 
   59     elif default == 
"yes":
 
   64         raise ValueError(
"invalid default answer: '%s'" % default)
 
   67         sys.stdout.write(question + prompt)
 
   68         choice = 
input().lower()
 
   69         if default 
is not None and choice == 
'':
 
   74             sys.stdout.write(
"Please respond with 'yes' or 'no' " 
   81     elif model == 
"quadratic":
 
   83     elif model == 
"quadratic-uv" or model == 
"quadratic-uv-abs":
 
   85     elif model == 
"quadratic-uv-quadratic" or model == 
"quadratic-uv-quadratic-abs":
 
   95     elif model == 
"quadratic":
 
   97     elif model == 
"quadratic-uv":
 
   98         return [u * x2, v * x2, x2,
 
  101     elif model == 
"quadratic-uv-abs":
 
  104         return [u * x2, v * x2, x2,
 
  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, 
 
  111     elif model == 
"quadratic-uv-quadratic-abs":
 
  116         return [u2 * x2, u * x2, v2 * x2, v * x2, x2, 
 
  117                 u2 * x,  u * x,  v2 * x,  v * x, x, 
 
  123     c0 = classifier.intercept_
 
  124     return not hasattr(c0, 
"__len__");
 
  129     c0 = classifier.intercept_
 
  130     param = DepthCalibrationParameter()
 
  132         print(
"parameters are list")
 
  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]
 
  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]
 
  167     global xs, ys, classifier, u_min, u_max, v_min, v_max, raw_xs
 
  171         if (uu, vv) 
in value_cache:
 
  172             zs = value_cache[(uu, vv)]
 
  174                 if abs(z - y) < eps_z:
 
  175                     print(
"duplicated value")
 
  178                     value_cache[(uu, vv)].append(y)
 
  180             value_cache[(uu, vv)] = [y]
 
  186         if u > u_min 
and u < u_max 
and v < v_max 
and v > v_min:
 
  191                 classifier.fit(xs, ys)
 
  194                 except rospy.service.ServiceException 
as e:
 
  195                     rospy.logfatal(
"failed to call service: %s" % (e.message))
 
  198             except Exception 
as e:
 
  199                 rospy.logwarn(
"failed to print model: %s" % e.message)
 
  202                 print(
"(%d, %d) is out of range" % (u, v))
 
  205     global xs, ys, classifier, u_min, u_max, v_min, v_max, raw_xs
 
  207     x = msg.observed_depth
 
  211     if math.isnan(x) 
or math.isnan(y):
 
  213     processData(x, y, u, v, msg.center_u, msg.center_v)
 
  218         return "%f|u| + %f|v| + %f" % (c[0], c[1], c[2])
 
  220         return "%fu + %fv + %f" % (c[0], c[1], c[2])
 
  223         return "%f|u|^2 + %f|u| + %f|v|^2 + %f|v| + %f" % (c[0], c[1], c[2], c[3], c[4])
 
  225         return "%fu^2 + %fu + %fv^2 + %fv + %f" % (c[0], c[1], c[2], c[3], c[4])
 
  230     i = classifier.intercept_
 
  231     if model == 
"linear":
 
  232         return "%fz + %f\n(score: %f)" % (
 
  234             classifier.score(xs, ys))
 
  235     elif model == 
"quadratic":
 
  236         return "%fz^2 + %fz + %f\n(score: %f)" % (
 
  240             classifier.score(xs, ys))
 
  241     elif model == 
"quadratic-uv":
 
  242         return "(%s)z^2 +\n(%s)z +\n%s\n(score: %f)" % (
 
  246             classifier.score(xs, ys))
 
  247     elif model == 
"quadratic-uv-abs":
 
  248         return "(%s)z^2 +\n(%s)z +\n%s\n(score: %f)" % (
 
  252             classifier.score(xs, ys))
 
  253     elif model == 
"quadratic-uv-quadratic":
 
  254         return "(%s)z^2 +\n(%s)z +\n%s\n(score: %f)" % (
 
  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)" % (
 
  264             classifier.score(xs, ys))
 
  269     i = classifier.intercept_
 
  270     if model == 
"linear":
 
  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":
 
  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":
 
  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":
 
  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))
 
  301     global xs, ax, width, height
 
  302     if rospy.is_shutdown():
 
  310             plt.xlabel(
'Z from depth image')
 
  311             plt.ylabel(
'Z from checker board')
 
  315                         ys[:-1], s=10, c=
'b', zorder=10, alpha=0.1)
 
  317                         [ys[-1]], s=10, c=
'r', zorder=10, alpha=1.0)
 
  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)
 
  325                                width / 2, height / 2,
 
  326                                width / 2, height / 2,
 
  328                     linewidth=2, color=
'red', alpha=0.5)
 
  329             plt.text(xmin, xmax - 0.1,
 
  335             pub_image.publish(bridge.cv2_to_imgmsg(img, 
"bgr8"))
 
  339             w, h = fig.canvas.get_width_height()
 
  340             plot_img = np.fromstring(fig.canvas.tostring_rgb(), dtype=np.uint8)
 
  342             plot_img.shape = (h, w, 3)
 
  344             pub_error_plot.publish(bridge.cv2_to_imgmsg(plot_img, 
"bgr8"))
 
  345         except Exception 
as e:
 
  346             rospy.logerr(e.message)
 
  351     img = np.tile(np.uint8([0,0,0]), (height // 10, width // 10, 1))
 
  353     for (u, v) 
in value_cache.keys():
 
  354         min_color = np.uint8([255, 0, 0])
 
  355         max_color = np.uint8([0, 0, 255])
 
  358         if (uu, vv) 
in frequency:
 
  359             frequency[(uu, vv)] = frequency[(uu, vv)] + len(value_cache[(u, v)])
 
  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
 
  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)
 
  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:])
 
  389     if model 
not in MODELS:
 
  390         raise Exception(
"Unknown Model: %s" % (model))
 
  393         sub = rospy.Subscriber(
"depth_image_error/output", 
 
  394                                DepthErrorResult, callback)
 
  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)
 
  405         for row 
in csv.reader(open(args.csv, 
"rb")):
 
  413         classifier.fit(xs, ys)
 
  416         except rospy.service.ServiceException 
as e:
 
  417             rospy.logfatal(
"failed to call service: %s" % (e.message))
 
  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")
 
  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)
 
  433             if model == 
"quadratic-uv-abs" or model == 
"quadratic-uv-quadratic-abs":
 
  438             with open(yaml_filename, 
"w") 
as f:
 
  440 coefficients2: [%s, %s, %s, %s, %s] 
  441 coefficients1: [%s, %s, %s, %s, %s] 
  442 coefficients0: [%s, %s, %s, %s, %s] 
  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_),
 
  450 if __name__ == 
"__main__":
 
  451     rospy.init_node(
"depth_error_logistic_regression")