14     bin_index = int(msg.true_depth / grid)
 
   15     if bin_index 
not in bins:
 
   17     err = msg.true_depth - msg.observed_depth
 
   18     bins[bin_index].append((msg, err))
 
   19     for bin_index, msg_and_errs 
in bins.items():
 
   20         if len(msg_and_errs) < 5:
 
   22         print(
"Bin: {0}m ~ {1}m".format(grid * bin_index, grid * (bin_index + 1)))
 
   23         print(
"   Sample:", len(msg_and_errs))
 
   24         errs = [err 
for (msg, err) 
in msg_and_errs]
 
   25         mean = np.mean(errs, axis=0)
 
   26         stddev = np.std(errs, axis=0)
 
   28         print(
"   Stddev:", stddev)
 
   29     data.xs.append(msg.true_depth)
 
   30     data.ys.append(msg.observed_depth)
 
   32     writer.writerow([msg.true_depth, msg.observed_depth])
 
   35 if __name__ == 
"__main__":
 
   36     rospy.init_node(
"plot_depth_error")
 
   37     csv_path = rospy.get_param(
"~csv_path", 
"output.csv")
 
   38     pub = rospy.Publisher(
"~scatter", PlotData, queue_size=1)
 
   39     f = open(csv_path, 
"w")
 
   40     writer = csv.writer(f)
 
   41     sub = rospy.Subscriber(
"/depth_image_error/output", DepthErrorResult, callback)