bbox_transform.py
Go to the documentation of this file.
00001 import numpy as np
00002 from bbox import bbox_overlaps_cython
00003 
00004 
00005 def bbox_overlaps(boxes, query_boxes):
00006     return bbox_overlaps_cython(boxes, query_boxes)
00007 
00008 
00009 def bbox_overlaps_py(boxes, query_boxes):
00010     """
00011     determine overlaps between boxes and query_boxes
00012     :param boxes: n * 4 bounding boxes
00013     :param query_boxes: k * 4 bounding boxes
00014     :return: overlaps: n * k overlaps
00015     """
00016     n_ = boxes.shape[0]
00017     k_ = query_boxes.shape[0]
00018     overlaps = np.zeros((n_, k_), dtype=np.float)
00019     for k in range(k_):
00020         query_box_area = (query_boxes[k, 2] - query_boxes[k, 0] + 1) * (query_boxes[k, 3] - query_boxes[k, 1] + 1)
00021         for n in range(n_):
00022             iw = min(boxes[n, 2], query_boxes[k, 2]) - max(boxes[n, 0], query_boxes[k, 0]) + 1
00023             if iw > 0:
00024                 ih = min(boxes[n, 3], query_boxes[k, 3]) - max(boxes[n, 1], query_boxes[k, 1]) + 1
00025                 if ih > 0:
00026                     box_area = (boxes[n, 2] - boxes[n, 0] + 1) * (boxes[n, 3] - boxes[n, 1] + 1)
00027                     all_area = float(box_area + query_box_area - iw * ih)
00028                     overlaps[n, k] = iw * ih / all_area
00029     return overlaps
00030 
00031 
00032 def clip_boxes(boxes, im_shape):
00033     """
00034     Clip boxes to image boundaries.
00035     :param boxes: [N, 4* num_classes]
00036     :param im_shape: tuple of 2
00037     :return: [N, 4* num_classes]
00038     """
00039     # x1 >= 0
00040     boxes[:, 0::4] = np.maximum(np.minimum(boxes[:, 0::4], im_shape[1] - 1), 0)
00041     # y1 >= 0
00042     boxes[:, 1::4] = np.maximum(np.minimum(boxes[:, 1::4], im_shape[0] - 1), 0)
00043     # x2 < im_shape[1]
00044     boxes[:, 2::4] = np.maximum(np.minimum(boxes[:, 2::4], im_shape[1] - 1), 0)
00045     # y2 < im_shape[0]
00046     boxes[:, 3::4] = np.maximum(np.minimum(boxes[:, 3::4], im_shape[0] - 1), 0)
00047     return boxes
00048 
00049 def filter_boxes(boxes, min_size):
00050     """
00051     filter small boxes.
00052     :param boxes: [N, 4* num_classes]
00053     :param min_size:
00054     :return: keep:
00055     """
00056     ws = boxes[:, 2] - boxes[:, 0] + 1
00057     hs = boxes[:, 3] - boxes[:, 1] + 1
00058     keep = np.where((ws >= min_size) & (hs >= min_size))[0]
00059     return keep
00060 
00061 def nonlinear_transform(ex_rois, gt_rois):
00062     """
00063     compute bounding box regression targets from ex_rois to gt_rois
00064     :param ex_rois: [N, 4]
00065     :param gt_rois: [N, 4]
00066     :return: [N, 4]
00067     """
00068     assert ex_rois.shape[0] == gt_rois.shape[0], 'inconsistent rois number'
00069 
00070     ex_widths = ex_rois[:, 2] - ex_rois[:, 0] + 1.0
00071     ex_heights = ex_rois[:, 3] - ex_rois[:, 1] + 1.0
00072     ex_ctr_x = ex_rois[:, 0] + 0.5 * (ex_widths - 1.0)
00073     ex_ctr_y = ex_rois[:, 1] + 0.5 * (ex_heights - 1.0)
00074 
00075     gt_widths = gt_rois[:, 2] - gt_rois[:, 0] + 1.0
00076     gt_heights = gt_rois[:, 3] - gt_rois[:, 1] + 1.0
00077     gt_ctr_x = gt_rois[:, 0] + 0.5 * (gt_widths - 1.0)
00078     gt_ctr_y = gt_rois[:, 1] + 0.5 * (gt_heights - 1.0)
00079 
00080     targets_dx = (gt_ctr_x - ex_ctr_x) / (ex_widths + 1e-14)
00081     targets_dy = (gt_ctr_y - ex_ctr_y) / (ex_heights + 1e-14)
00082     targets_dw = np.log(gt_widths / ex_widths)
00083     targets_dh = np.log(gt_heights / ex_heights)
00084 
00085     targets = np.vstack(
00086         (targets_dx, targets_dy, targets_dw, targets_dh)).transpose()
00087     return targets
00088 
00089 
00090 def nonlinear_pred(boxes, box_deltas):
00091     """
00092     Transform the set of class-agnostic boxes into class-specific boxes
00093     by applying the predicted offsets (box_deltas)
00094     :param boxes: !important [N 4]
00095     :param box_deltas: [N, 4 * num_classes]
00096     :return: [N 4 * num_classes]
00097     """
00098     if boxes.shape[0] == 0:
00099         return np.zeros((0, box_deltas.shape[1]))
00100 
00101     boxes = boxes.astype(np.float, copy=False)
00102     widths = boxes[:, 2] - boxes[:, 0] + 1.0
00103     heights = boxes[:, 3] - boxes[:, 1] + 1.0
00104     ctr_x = boxes[:, 0] + 0.5 * (widths - 1.0)
00105     ctr_y = boxes[:, 1] + 0.5 * (heights - 1.0)
00106 
00107     dx = box_deltas[:, 0::4]
00108     dy = box_deltas[:, 1::4]
00109     dw = box_deltas[:, 2::4]
00110     dh = box_deltas[:, 3::4]
00111 
00112     pred_ctr_x = dx * widths[:, np.newaxis] + ctr_x[:, np.newaxis]
00113     pred_ctr_y = dy * heights[:, np.newaxis] + ctr_y[:, np.newaxis]
00114     pred_w = np.exp(dw) * widths[:, np.newaxis]
00115     pred_h = np.exp(dh) * heights[:, np.newaxis]
00116 
00117     pred_boxes = np.zeros(box_deltas.shape)
00118     # x1
00119     pred_boxes[:, 0::4] = pred_ctr_x - 0.5 * (pred_w - 1.0)
00120     # y1
00121     pred_boxes[:, 1::4] = pred_ctr_y - 0.5 * (pred_h - 1.0)
00122     # x2
00123     pred_boxes[:, 2::4] = pred_ctr_x + 0.5 * (pred_w - 1.0)
00124     # y2
00125     pred_boxes[:, 3::4] = pred_ctr_y + 0.5 * (pred_h - 1.0)
00126 
00127     return pred_boxes
00128 
00129 
00130 def iou_transform(ex_rois, gt_rois):
00131     """ return bbox targets, IoU loss uses gt_rois as gt """
00132     assert ex_rois.shape[0] == gt_rois.shape[0], 'inconsistent rois number'
00133     return gt_rois
00134 
00135 
00136 def iou_pred(boxes, box_deltas):
00137     """
00138     Transform the set of class-agnostic boxes into class-specific boxes
00139     by applying the predicted offsets (box_deltas)
00140     :param boxes: !important [N 4]
00141     :param box_deltas: [N, 4 * num_classes]
00142     :return: [N 4 * num_classes]
00143     """
00144     if boxes.shape[0] == 0:
00145         return np.zeros((0, box_deltas.shape[1]))
00146 
00147     boxes = boxes.astype(np.float, copy=False)
00148     x1 = boxes[:, 0]
00149     y1 = boxes[:, 1]
00150     x2 = boxes[:, 2]
00151     y2 = boxes[:, 3]
00152 
00153     dx1 = box_deltas[:, 0::4]
00154     dy1 = box_deltas[:, 1::4]
00155     dx2 = box_deltas[:, 2::4]
00156     dy2 = box_deltas[:, 3::4]
00157 
00158     pred_boxes = np.zeros(box_deltas.shape)
00159     # x1
00160     pred_boxes[:, 0::4] = dx1 + x1[:, np.newaxis]
00161     # y1
00162     pred_boxes[:, 1::4] = dy1 + y1[:, np.newaxis]
00163     # x2
00164     pred_boxes[:, 2::4] = dx2 + x2[:, np.newaxis]
00165     # y2
00166     pred_boxes[:, 3::4] = dy2 + y2[:, np.newaxis]
00167 
00168     return pred_boxes
00169 
00170 
00171 # define bbox_transform and bbox_pred
00172 bbox_transform = nonlinear_transform
00173 bbox_pred = nonlinear_pred


rail_object_detector
Author(s):
autogenerated on Sat Jun 8 2019 20:26:29